ROS源码学习分享_8_advertise


        在前面的章节中我们观看了NodeHandle句柄启动后背后的一些行为,在这一章我们将看一下Nodehandle句柄是怎么创建发布者的。

        在讨论之前,我们昨天在DDS的案例代码分析中也看到了拥有类似功能的模块,域参与者。域参与者也同样可以创建发布订阅者节点,还可以创建话题。那他们是否承担相同的功能呢?

        在这里我们需要对他们作出一些比较:

ROS中的NodeHandle


        在ROS中,NodeHandle是一个节点的句柄,它主要用于以下任务:

1.创建发布者(Publisher)和订阅者(Subscriber):通过NodeHandle,你可以创建发布者和订阅者,以便节点可以与ROS中的其他节点通信。
2.服务和客户端:NodeHandle还用于创建服务和客户端,以实现同步通信。
3.参数服务器交互:NodeHandle可以用来访问和修改ROS参数服务器上的参数。
        NodeHandle实际上是节点与ROS主节点(Master)之间的接口,它提供了一个简化的API来处理节点的通信需求。

DDS中的域参与者(Domain Participant)


        在DDS中,域参与者(Domain Participant)是一个更为基础的实体,它在整个DDS系统中扮演了更核心的角色:

1.创建发布者(Publisher)和订阅者(Subscriber):域参与者是DDS的核心,它通过其创建发布者和订阅者,这些发布者和订阅者负责数据的发布和接收。
2.管理QoS策略:域参与者负责管理DDS的质量服务(QoS)策略,这些策略控制了数据传输的行为和特性。
3.域管理:域参与者定义了DDS系统中的域,一个域是逻辑上的通信隔离区,不同域中的参与者无法相互通信。
4.资源管理:域参与者负责分配和管理DDS系统的资源,包括内存、线程和其他系统资源。
 

责任和功能的对比


        尽管NodeHandle和域参与者在创建发布者方面有相似的功能,但它们在系统中的责任和范围是不同的:

1.抽象层次:NodeHandle是一个更高层的抽象,它隐藏了很多底层细节,提供了一个简化的API。而域参与者则更接近DDS的核心机制,提供了更多的控制和配置选项。
2.系统角色:NodeHandle主要是一个节点的接口,用于处理通信和参数管理。而域参与者是DDS的基础组件,负责管理整个DDS通信域及其资源。
3.复杂度:NodeHandle的使用相对简单,适合快速开发和部署。而域参与者提供了更复杂和细粒度的控制,适合对系统性能和行为有更高要求的应用。
        因此,尽管NodeHandle和域参与者都用于创建发布者,它们在系统中的角色和职责范围存在显著差异。NodeHandle是ROS中的一个高层接口,简化了节点的通信和参数管理。而域参与者是DDS系统的核心组件,提供了全面的资源管理和QoS配置。两者在设计上都有其特定的目标和适用场景,因此不能完全视为等同的概念。

代码解析


        在了解了他们之间的差别之后,我们来看下这句代码背后的行为。代码如下:

  ros::Publisher pub =n.advertise<D::sample::PublishInfo>("/DD", 1000);

        他会先走Nodehandle里面这个模版函数:

    template <class M>
    Publisher advertise(const std::string& topic, uint32_t queue_size, bool latch = false)
    {
      AdvertiseOptions ops;
      ops.template init<M>(topic, queue_size);
      ops.latch = latch;
      return advertise(ops);
    }

        AdvertiseOptions是一个类,用于配置话题发布选项,与DDS相比,有点类似于qos的功能。不过qos比他的功能强太多了,在这里AdvertiseOptions 提供了一些基本的配置选项,比如话题名称、队列大小和是否启用latch。相比之下,DDS 的 QoS 配置更为详细和复杂,能够精确控制数据传输和存储的行为。此外有些朋友可能对这种模版调用有点不认识,在这里说明一下。在C++中,如果类成员函数是一个模板函数,而我们在调用它时需要显式指定模板参数,就需要使用template 关键字。这是因为编译器在解析模板代码时,需要明确区分模板成员函数调用和普通成员函数调用。特别是当成员函数是一个模板函数时,使用template 关键字是为了避免语法上的二义性。

1.需要template关键字:当你在模板类中调用模板成员函数,且编译器需要明确知道这是一个模板函数时。
2.不需要template关键字:当编译器能够从上下文中明确解析出成员函数是一个模板函数,或者成员函数不是模板函数时。


        在这里因为init是advertiseOptions类中的一个模版函数,且上下文没有,就需要写template。其实你不写也没事,是有些编译器会报错,最好写上这里。这里的latch是发布者是否“锁定”最新的消息,以确保新订阅者能够接收到最新的消息。当一个发布者被设置为latch模式时,它会缓存最后发布的消息,并在新的订阅者连接时自动向其发送这条缓存的消息。这对于一些需要确保新订阅者能够立即获得最新数据的场景特别有用,例如状态信息或配置参数的发布。

AdvertiseOptions的初始化代码如下:

  template <class M>
  void init(const std::string& _topic, uint32_t _queue_size,
            const SubscriberStatusCallback& _connect_cb = SubscriberStatusCallback(),
            const SubscriberStatusCallback& _disconnect_cb = SubscriberStatusCallback())
  {
    topic = _topic;
    queue_size = _queue_size;
    connect_cb = _connect_cb;
    disconnect_cb = _disconnect_cb;
    md5sum = message_traits::md5sum<M>();
    datatype = message_traits::datatype<M>();
    message_definition = message_traits::definition<M>();
    has_header = message_traits::hasHeader<M>();
  }

       这里的topic就是设置的话题,后面的分别是发布队列长度,链接回调,中断回调,校验和,数据类型,消息定义,是否包含头部等信息。在设置了opt之后他就会启动真正的advertise.

        advertise代码如下:

        

Publisher NodeHandle::advertise(AdvertiseOptions& ops)
{
  ops.topic = resolveName(ops.topic);
  if (ops.callback_queue == 0)
  {
    if (callback_queue_)
    {
      ops.callback_queue = callback_queue_;
    }
    else
    {
      ops.callback_queue = getGlobalCallbackQueue();
    }
  }

  SubscriberCallbacksPtr callbacks(boost::make_shared<SubscriberCallbacks>(ops.connect_cb, ops.disconnect_cb, 
                                                                           ops.tracked_object, ops.callback_queue));

  Publisher pub(ops.topic, ops.md5sum, ops.datatype, ops.latch, *this, callbacks);

  if (ops.latch) {
    callbacks->push_latched_message_ = pub.getLastMessageCallback();
  }

  if (TopicManager::instance()->advertise(ops, callbacks))
  {

    {
      boost::mutex::scoped_lock lock(collection_->mutex_);
      collection_->pubs_.push_back(pub.impl_);
    }

    return pub;
  }

  return Publisher();
}

        上面的代码主要是考察nodehandle是私有的还是公有的,决定最终的话题名。核心代码就两个步骤

        1.构造了一个pub发射器,这里面有一个回调函数组,用于处理订阅者连接的一些行为,我们主要看通信所以不用理他。

        2.他调用了topicManager里面的advertise

        跑一下题,我们还记的最开始TopicManager启动之后发生了什么吗?他绑定了xml_rpc的回调函数,然后把发布队列函数与信号槽进行绑定。但是当时深入没写,nodehandle句柄与rosmaster的关联在哪呢?这里需要说明rosmaster才是掌管整体的话题库的管理者,nodehandle注册的话题名必须要得到master的认可,而这里并没有与rosmaster相关联的实体。因此引入就是XMLRPCmanager。它通过xml为形式进行客户端与服务端的连接。我们回到Nodehandle节点中XMLRPCManager启动的代码去看看,代码如下:

void XMLRPCManager::start()
{
  shutting_down_ = false;
  port_ = 0;
  bind("getPid", getPid);

  bool bound = server_.bindAndListen(0);
  (void) bound;
  ROS_ASSERT(bound);
  port_ = server_.get_port();
  ROS_ASSERT(port_ != 0);

  std::stringstream ss;
  ss << "http://" << network::getHost() << ":" << port_ << "/";
  uri_ = ss.str();

  server_thread_ = boost::thread(boost::bind(&XMLRPCManager::serverThreadFunc, this));
}

        重点在最后一局他起了一个线程去执行一个函数,该函数核心代码如下:

void XMLRPCManager::serverThreadFunc()
{
  disableAllSignalsInThisThread();

  while(!shutting_down_)
  {
    {
      boost::mutex::scoped_lock lock(added_connections_mutex_);
      S_ASyncXMLRPCConnection::iterator it = added_connections_.begin();
      S_ASyncXMLRPCConnection::iterator end = added_connections_.end();
      for (; it != end; ++it)
      {
        (*it)->addToDispatch(server_.get_dispatch());
        connections_.insert(*it);
      }

      added_connections_.clear();
    }

这时候我们看见了,XMLPRC里面有循环在不断轮转,它不断地将新注册的话题与发布器信息添加到处理队列中,而xmlrpc存在一个处理器,也在不断发布处理队列的消息给rosmaster。

        回归主题,在TopicManager的advertise代码如下:

bool TopicManager::advertise(const AdvertiseOptions& ops, const SubscriberCallbacksPtr& callbacks)
{
  if (ops.datatype == "*")
  {
    std::stringstream ss;
    ss << "Advertising with * as the datatype is not allowed.  Topic [" << ops.topic << "]";
    throw InvalidParameterException(ss.str());
  }

  if (ops.md5sum == "*")
  {
    std::stringstream ss;
    ss << "Advertising with * as the md5sum is not allowed.  Topic [" << ops.topic << "]";
    throw InvalidParameterException(ss.str());
  }

  if (ops.md5sum.empty())
  {
    throw InvalidParameterException("Advertising on topic [" + ops.topic + "] with an empty md5sum");
  }

  if (ops.datatype.empty())
  {
    throw InvalidParameterException("Advertising on topic [" + ops.topic + "] with an empty datatype");
  }

  if (ops.message_definition.empty())
  {
    ROS_WARN("Advertising on topic [%s] with an empty message definition.  Some tools (e.g. rosbag) may not work correctly.", ops.topic.c_str());
  }

  PublicationPtr pub;

  {
    boost::recursive_mutex::scoped_lock lock(advertised_topics_mutex_);

    if (isShuttingDown())
    {
      return false;
    }

    pub = lookupPublicationWithoutLock(ops.topic);
    if (pub && pub->getNumCallbacks() == 0)
    {
      pub.reset();
    }

    if (pub)
    {
      if (pub->getMD5Sum() != ops.md5sum)
      {
        ROS_ERROR("Tried to advertise on topic [%s] with md5sum [%s] and datatype [%s], but the topic is already advertised as md5sum [%s] and datatype [%s]",
                  ops.topic.c_str(), ops.md5sum.c_str(), ops.datatype.c_str(), pub->getMD5Sum().c_str(), pub->getDataType().c_str());
        return false;
      }

      pub->addCallbacks(callbacks);

      return true;
    }

    pub = PublicationPtr(boost::make_shared<Publication>(ops.topic, ops.datatype, ops.md5sum, ops.message_definition, ops.queue_size, false, ops.has_header));
    pub->addCallbacks(callbacks);
    advertised_topics_.push_back(pub);
  }


  {
    boost::mutex::scoped_lock lock(advertised_topic_names_mutex_);
    advertised_topic_names_.push_back(ops.topic);
  }

  // Check whether we've already subscribed to this topic.  If so, we'll do
  // the self-subscription here, to avoid the deadlock that would happen if
  // the ROS thread later got the publisherUpdate with its own XMLRPC URI.
  // The assumption is that advertise() is called from somewhere other
  // than the ROS thread.
  bool found = false;
  SubscriptionPtr sub;
  {
    boost::mutex::scoped_lock lock(subs_mutex_);

    for (L_Subscription::iterator s = subscriptions_.begin();
         s != subscriptions_.end() && !found; ++s)
    {
      if ((*s)->getName() == ops.topic && md5sumsMatch((*s)->md5sum(), ops.md5sum) && !(*s)->isDropped())
      {
        found = true;
        sub = *s;
        break;
      }
    }
  }

  if(found)
  {
    sub->addLocalConnection(pub);
  }

  XmlRpcValue args, result, payload;
  args[0] = this_node::getName();
  args[1] = ops.topic;
  args[2] = ops.datatype;
  args[3] = xmlrpc_manager_->getServerURI();
  master::execute("registerPublisher", args, result, payload, true);

  return true;
}

        我们可以看到在这个函数中先做了校验然后,所以我们如果要更改使用的传输数据结构如protobuf这里就要改,不然这一步就走不过去。之后创建一个PublicationPtr类型的发布器对象,随后将这个发布器对象添加到列表中去,最后使用master::execute的registerPublisher的RPC方法进行注册。具体行为为:

1.锁定和检查关闭状态:使用 advertised_topics_mutex_ 锁定互斥量,以确保线程安全。检查系统是否正在关闭,如果是,则直接返回 false。
2.查找现有的发布者:尝试查找是否已经有该主题的发布者存在。如果存在并且没有回调,则重置(删除/重新创建)它。
3.验证 md5sum:如果找到一个现有的发布者但 md5sum 不匹配,则记录错误并返回 false。
4.创建新的发布者:如果没有找到现有的发布者,则创建一个新的 Publication 对象,并将其添加到 advertised_topics_ 列表中。
        值得注意的是   pub = lookupPublicationWithoutLock(ops.topic);尝试查找是否已有该主题的发布者。如果找不到,则pub会是nullptr。那后面到下一个pub被赋值之前都不会执行了。

bool found = false;
SubscriptionPtr sub;
{
  boost::mutex::scoped_lock lock(subs_mutex_);

  for (L_Subscription::iterator s = subscriptions_.begin(); s != subscriptions_.end() && !found; ++s) {
    if ((*s)->getName() == ops.topic && md5sumsMatch((*s)->md5sum(), ops.md5sum) && !(*s)->isDropped()) {
      found = true;
      sub = *s;
      break;
    }
  }
}

if (found) {
  sub->addLocalConnection(pub);
}

        这一段主要是锁定和检查现有订阅者:锁定 subs_mutex_,然后遍历 subscriptions_ 列表,检查是否有匹配的订阅者。添加本地连接:如果找到匹配的订阅者,则将新创建的发布者添加为本地连接。这是为了处理进程内通信,避免潜在的死锁。如果找到匹配的订阅者,则调用 sub->addLocalConnection(pub); 添加本地连接。这处理了进程内通信

XmlRpcValue args, result, payload;
args[0] = this_node::getName();
args[1] = ops.topic;
args[2] = ops.datatype;
args[3] = xmlrpc_manager_->getServerURI();
master::execute("registerPublisher", args, result, payload, true);

        这段代码使用 XML-RPC 调用将新创建的发布者注册到 ROS 主节点,以便其他节点可以发现该发布者。如果一切正常,函数返回true,表示发布者创建和注册成功。通过 XML-RPC 调用registerPublisher 将新创建的发布者注册到 ROS 主节点。这处理了进程间通信,允许其他节点发现并与新发布者进行通信。即使存在进程内通信,发布者仍会向主节点注册,以便其他进程中的节点可以订阅该主题。主节点负责将订阅者和发布者的信息传递给各个节点,从而实现跨进程通信。

        再之后就返回了NodeHandle这段代码

  if (TopicManager::instance()->advertise(ops, callbacks))
  {

    {
      boost::mutex::scoped_lock lock(collection_->mutex_);
      collection_->pubs_.push_back(pub.impl_);
    }

    return pub;
  }

  return Publisher();
}

        如果这个返回False则返回一个默认的发布者,如果成功则把collection_锁住,在锁定的情况下,将 pub.impl_ 添加到 collection_ 的 pubs_ 列表中。pub.impl_ 是 pub 对象的内部实现指针,它指向具体的 Publication 对象。

        梳理:advertise首先会进入nodehandle头文件的advertise版本,然后创建了一个AdvertiseOptions用于配置话题发布选项。之后将AdvertiseOptions传递给实现版本的advertise,在该版本的advertise中创建一个使用使用resolveName函数将相对话题名称解析为全局唯一名称。之后检查 ops.callback_queue 是否为 0,如果是,则尝试使用 NodeHandle 的回调队列 callback_queue_,如果没有,则使用全局回调队列 getGlobalCallbackQueue()。在之后创建了一个pub发射器并调用了TopicManager里面的advertise,在TopicManager::advertise我先做了校验然后,之后创建一个PublicationPtr类型的发布器对象,随后将这个发布器对象添加到列表中去,最后使用master::execute的registerPublisher的RPC方法进行注册。通过这些步骤,代码确保每个话题的发布者被正确注册并处理自订阅,避免可能的死锁,同时保证数据的一致性和有效性。在确保注册成功或已经有可靠的相同发布者,则将此发布者加入到发布者集合队列中,如果失败则返回一个默认的发布者。

  • 18
    点赞
  • 7
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值