@[TOC]ROS源代码之Publish底层实现
ROS源代码之Publish底层实现
在之前对ROS的源码的学习中,基本弄清楚了ROS的topic通信方式中,节点发布/订阅的机制和原理,可以说解释了节点与master之间的交流方式。但是对于节点与节点之间通信的具体过程,却一笔带过,所以这次通过再次阅读这部分源码,来明确节点在advertise之后,注册完成之后,publish消息时底层通信的逻辑和形式。
本次源码阅读主要通过dfs的方式来进行。首先是ROS wiki提供的发布者节点发布信息时的最表层调用:
#include "ros/ros.h"
#include "std_msgs/String.h"
#include <sstream>
int main(int argc, char **argv)
{
ros::init(argc, argv, "talker");
ros::NodeHandle n;
ros::Publisher chatter_pub = n.advertise<std_msgs::String>("chatter", 1000);
ros::Rate loop_rate(10);
int count = 0;
while (ros::ok())
{
std_msgs::String msg;
std::stringstream ss;
ss << "hello world " << count;
msg.data = ss.str();
ROS_INFO("%s", msg.data.c_str());
chatter_pub.publish(msg);
ros::spinOnce();
loop_rate.sleep();
}
return 0;
}
可以看到,其中调用publish函数的正是之前我们使用nodehandle对象的advertise注册发布者时所返回的publisher类对象chatter_pub,传入的参数时我们自定义的msg类型。
我们在roscpp包中寻找相关的代码,如下是在publisher.h中所定义的两种重载的模板函数,分别用来应传入参数类型不同的的两种情况。
······
//共享指针类型的引用传参
template <typename M>
void publish(const boost::shared_ptr<M>& message) const
{
using namespace serialization;
if (!impl_)
{
ROS_ASSERT_MSG(false, "Call to publish() on an invalid Publisher");
return;
}
if (!impl_->isValid())
{
ROS_ASSERT_MSG(false, "Call to publish() on an invalid Publisher (topic [%s])", impl_->topic_.c_str());
return;
}
ROS_ASSERT_MSG(impl_->md5sum_ == "*" || std::string(mt::md5sum<M>(*message)) == "*" || impl_->md5sum_ == mt::md5sum<M>(*message),
"Trying to publish message of type [%s/%s] on a publisher with type [%s/%s]",
mt::datatype<M>(*message), mt::md5sum<M>(*message),
impl_->datatype_.c_str(), impl_->md5sum_.c_str());
SerializedMessage m;
m.type_info = &typeid(M);
m.message = message;
// 这里使用ref函数是给bind绑定的参数传入ref()引用包装类型,使参数为引用传递;
// 使用bind应该是为了把message绑定给serializeMessage
publish(boost::bind(serializeMessage<M>, boost::ref(*message)), m);
}
// M类型的引用传参 泛型
template <typename M>
void publish(const M& message) const
{
using namespace serialization;
namespace mt = ros::message_traits;
if (!impl_)
{
ROS_ASSERT_MSG(false, "Call to publish() on an invalid Publisher");
return;
}
if (!impl_->isValid())
{
ROS_ASSERT_MSG(false, "Call to publish() on an invalid Publisher (topic [%s])", impl_->topic_.c_str());
return;
}
ROS_ASSERT_MSG(impl_->md5sum_ == "*" || std::string(mt::md5sum<M>(message)) == "*" || impl_->md5sum_ == mt::md5sum<M>(message),
"Trying to publish message of type [%s/%s] on a publisher with type [%s/%s]",
mt::datatype<M>(message), mt::md5sum<M>(message),
impl_->datatype_.c_str(), impl_->md5sum_.c_str());
SerializedMessage m;
publish(boost::bind(serializeMessage<M>, boost::ref(message)), m);
}
······
他们最终都调用的publish函数在publisher.cpp中实现,具体如下:
········
// publish函数
void Publisher::publish(const boost::function<SerializedMessage(void)>& serfunc, SerializedMessage& m) const
{
// impl是否存在
if (!impl_)
{
ROS_ASSERT_MSG(false, "Call to publish() on an invalid Publisher (topic [%s])", impl_->topic_.c_str());
return;
}
// impl是否可用
if (!impl_->isValid())
{
ROS_ASSERT_MSG(false, "Call to publish() on an invalid Publisher (topic [%s])", impl_->topic_.c_str());
return;
}
// topicManager的单例调用publish
TopicManager::instance()->publish(impl_->topic_, serfunc, m);
}
···········
其中的impl是publisher类在传参构造时的生成一个内部类对象,一般是由nodehandle类中的advertise函数,获取到ops的相关信息并传进来生成的impl_对象。也就是说在注册成功后才会存在的一个对象。
显然之后,Publisher.publish()函数让TopicManager的唯一实例调用了