準備
ROS1 noeticの通常のインストールを完了させる。
vscodeでコードを追っていくため、これとC/C++拡張をインストールしておく。
workspaceを作り、roscommをクローンし、自前ビルドする。
cd
mkdir -p colcon_ws/src
cd colcon_ws/src
git clone https://github.com/ros/ros_comm.git
colcon build --catkin-skip-building-tests --cmake-args=-DCMAKE_BUILD_TYPE=Release
source ~/colcon_ws/install/setup.bash
~/colcon_wsでvscodeを開く。
vscodeで、C/C++ Extensionをインストールしている場合、インクルードパスに以下のように追記する(user名は置き換え)。
${workspaceFolder}/src/**
/opt/ros/noetic/include/**
これでvscodeでROS内部の通信周りの処理などを追えるようになった。
Advertise
チュートリアルの以下の行の、advertiseから見ていってみる。
ros::Publisher chatter_pub = n.advertise<std_msgs::String>("chatter", 1000);
node_handle.cpp
/**
* \brief Advertise a topic, simple version
*
* This call connects to the master to publicize that the node will be
* publishing messages on the given topic. This method returns a Publisher that allows you to
* publish a message on this topic.
*
* This version of advertise is a templated convenience function, and can be used like so
*
* ros::Publisher pub = handle.advertise<std_msgs::Empty>("my_topic", 1);
*
* \param topic Topic to advertise on
*
* \param queue_size Maximum number of outgoing messages to be
* queued for delivery to subscribers
*
* \param latch (optional) If true, the last message published on
* this topic will be saved and sent to new subscribers when they
* connect
*
* \return On success, a Publisher that, when it goes out of scope,
* will automatically release a reference on this advertisement. On
* failure, an empty Publisher.
*
* \throws InvalidNameException If the topic name begins with a
* tilde, or is an otherwise invalid graph resource name, or is an
* otherwise invalid graph resource name
*/
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); // template関数呼び出し
ops.latch = latch;
return advertise(ops);
}
ops.temprate init<M>(…)はテンプレート関数を明示的に呼び出す記述法らしい。このページに記載があった。
initの中を追いかけてみると、C++のtraitの仕組みを使ってメッセージ型から静的にMD5などを取り出して格納しているようだ。MD5などがどの時点で計算されているのかなどは引き続き調査する。message生成の過程で生成されているのではないかと考ええられる。
advertise_options.h
/**
* \brief templated helper function for automatically filling out md5sum, datatype and message definition
*
* \param M [template] Message type
* \param _topic Topic to publish on
* \param _queue_size Maximum number of outgoing messages to be queued for delivery to subscribers
* \param _connect_cb Function to call when a subscriber connects to this topic
* \param _disconnect_cb Function to call when a subscriber disconnects from this topic
*/
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>();
}
結局オーバーロードされたadvertise関数に行き着く。関連の引数はクラスAdvertiseOptionsにまとめられている。
node_handles.cpp
Publisher NodeHandle::advertise(AdvertiseOptions& ops)
{
// remapなど最終的なtopic名に書き換える処理
ops.topic = resolveName(ops.topic);
// callback_queueが登録されていなければ、登録。
// その際、既に取得したものがあればそれを使用。
if (ops.callback_queue == 0)
{
if (callback_queue_)
{
ops.callback_queue = callback_queue_;
}
else
{
ops.callback_queue = getGlobalCallbackQueue();
}
}
// latchの処理
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();
}
// 最終的にTopicManagerというクラスのadvertizeに行き着く。
// これがTopicの元締めのようだ。
if (TopicManager::instance()->advertise(ops, callbacks))
{
{
boost::mutex::scoped_lock lock(collection_->mutex_);
collection_->pubs_.push_back(pub.impl_);
}
return pub;
}
return Publisher();
}
TopicManager::advertise()を見てみると、いろいろと処理はありますが、最終的にはrosmasterに対しXMLRPCを通じてregisterPublisherという処理を呼び出しに行っているようです。これにより、rosmasterにadvertiseされたtopicとその発信元ノード名などが登録されると考えられます。
TopicManager.cpp
XmlRpcValue args, result, payload;
args[0] = this_node::getName();
args[1] = ops.topic;
args[2] = ops.datatype;
args[3] = xmlrpc_manager_->getServerURI(); // XMLRPCManagerPtr
master::execute("registerPublisher", args, result, payload, true);