環境
この記事は以下の環境で動いています。
項目 | 値 |
---|---|
CPU | Core i5-8250U |
Ubuntu | 20.04 |
ROS | Noetic |
インストールについてはROS講座02 インストールを参照してください。
またこの記事のプログラムはgithubにアップロードされています。ROS講座11 gitリポジトリを参照してください。
概要
ROSのノード間通信ではプロセス間通信のためにメモリコピーが発生し通信の遅延が存在します。特に画像はデータサイズが大きいために通信量や遅延が無視できない量になります。Nodeletを使うと記述の仕方が特殊になりますが、メモリコピー無しでノード間通信を行うことができます。
Nodeletとは通常のROSノードに当たる機能を持ったプログラムをプラグインの形で記述して、実行時には複数のプラグインを1つのプロセスで実行することでメモリコピーを回避して高速化を狙うという仕組みです。
ソースコード
takler
#include <ros/ros.h>
#include <nodelet/nodelet.h>
#include <pluginlib/class_list_macros.h>
#include <std_msgs/String.h>
namespace plugin_lecture
{
class plugin_nodelet_talker : public nodelet::Nodelet
{
public:
virtual void onInit();
void timer_callback(const ros::TimerEvent&);
private:
ros::NodeHandle nh_;
ros::NodeHandle pnh_;
ros::Publisher pub_;
ros::Timer timer_;
std::string content_;
};
void plugin_nodelet_talker::onInit()
{
NODELET_INFO("Talker Init");
nh_ = getNodeHandle();
pnh_ = getPrivateNodeHandle();
content_ = "hello";
pnh_.getParam("content", content_);
pub_ = nh_.advertise<std_msgs::String>("chatter", 10);
timer_ = nh_.createTimer(ros::Duration(1.0), &plugin_nodelet_talker::timer_callback, this);
}
void plugin_nodelet_talker::timer_callback(const ros::TimerEvent&)
{
NODELET_INFO("send: %s", content_.c_str());
std_msgs::String string_msg;
string_msg.data = content_;
pub_.publish(string_msg);
}
} // namespace plugin_lecture
PLUGINLIB_EXPORT_CLASS(plugin_lecture::plugin_nodelet_talker, nodelet::Nodelet);
- pluginの書き方の作法としてパッケージ名のnamespaceで全体をくくります。
- nodelet::Nodeletを継承したクラスとして機能を実装します。
- ROS_INFOの代わりにNODELET_INFO()を使用することが推奨されます。
- Nodeletの立ち上がり時にonInit()関数が呼ばれます。ここに機能を実装する。
- node handleはgetNodeHandle()、private node handleはgetPrivateNodeHandle()で取得します。これらを使ってpub、subを立ち上げたり、パラメーターを取得したりします。
- onInitの中で無限ループを書いてはいけません。処理が他のnodeletに渡されなくなってしまいます。繰り返し処理はタイマーを使いましょう。
- pluginlibを使っているので最後に
PLUGINLIB_EXPORT_CLASS()
を書く必要があります。
listener
#include <ros/ros.h>
#include <nodelet/nodelet.h>
#include <pluginlib/class_list_macros.h>
#include <std_msgs/String.h>
namespace plugin_lecture
{
class plugin_nodelet_listener : public nodelet::Nodelet
{
public:
virtual void onInit();
void chatter_callback(const std_msgs::String& string_msg);
private:
ros::NodeHandle nh_;
ros::Subscriber sub_;
};
void plugin_nodelet_listener::onInit()
{
NODELET_INFO("Listener Init");
nh_ = getNodeHandle();
sub_ = nh_.subscribe("chatter", 10, &plugin_nodelet_listener::chatter_callback, this);
}
void plugin_nodelet_listener::chatter_callback(const std_msgs::String& string_msg)
{
NODELET_INFO("recieve: %s", string_msg.data.c_str());
}
} // namespace plugin_lecture
PLUGINLIB_EXPORT_CLASS(plugin_lecture::plugin_nodelet_listener, nodelet::Nodelet)
注意点はほぼtalkerと一緒です。
CmakeList.txt
pluginlibの使い方の時とほぼ一緒です。それに加えてnodeletへの依存が入ります。生成されるのは実行ファイルではなくライブラリ(静的オブジェクト)なのでadd_libraryのところに書きます。
find_package(catkin REQUIRED COMPONENTS
pluginlib # この行を追加
nodelet # この行を追加
)
add_library(${PROJECT_NAME}
src/nodelets/plugin_nodelet_talker.cpp # この行を追加
src/nodelets/plugin_nodelet_listener.cpp # この行を追加
)
target_link_libraries(${PROJECT_NAME}
${catkin_LIBRARIES}
)
package.xmlに追加
依存の追加をします。またnodeletのpluginのファイルについての情報をnodeletに通知するためのファイルを作成してそれにパスを通す必要があります。
<build_depend>pluginlib</build_depend>
<build_depend>nodelet</build_depend>
<exec_depend>pluginlib</exec_depend>
<exec_depend>nodelet</exec_depend>
<export>
<nodelet plugin="${prefix}/nodelet_description.xml"/>
</export>
nodelet_description
nodeletへpluginの情報を通知するためのものです。libraryのpath要素はシェアードオブジェクトの場所を示すものです。今回は~/catkin_ws/devel/lib/libplugin_lecture.so
という場所にsoファイルができるので以下のようにlib/libplugin_lecture
と書きます。catkinのルールとしてlib/lib{パッケージ名}になるのが注意です。classタグではtalkerよlistenerで作ったc++のクラスについて記述します。typeはclass名、base_class_typeはその名の通りベースクラスの型名です。nameは何でもよいのですが{パッケージ名}/{class名}にするのが慣習です。
<library path="lib/libplugin_lecture">
<class name="plugin_lecture/plugin_nodelet_talker"
type="plugin_lecture::plugin_nodelet_talker"
base_class_type="nodelet::Nodelet">
<description>
</description>
</class>
<class name="plugin_lecture/plugin_nodelet_listener"
type="plugin_lecture::plugin_nodelet_listener"
base_class_type="nodelet::Nodelet">
<description>
</description>
</class>
</library>
launch(nodelet)
nodeletではmanagerというのを立ち会上げて、それにpluginを起動させるnodeを立ち上げます。実際の処理は全てmanagerのプロセスで実行されます。paramやremapも普通のnodeと同じように使用できます。
<?xml version="1.0"?>
<launch>
<arg name="manager_name" default="nodelet_manager" />
<arg name="manager_threads" default="4" />
<node pkg="nodelet" type="nodelet" name="$(arg manager_name)" args="manager" output="screen">
<param name="num_worker_threads" value="$(arg manager_threads)" />
</node>
<node pkg="nodelet" type="nodelet" name="node_loader0"
args="load plugin_lecture/plugin_nodelet_talker $(arg manager_name)" >
<remap from="chatter" to="chatter_alt" />
<param name="content" value="hello2" />
</node>
<node pkg="nodelet" type="nodelet" name="node_loader1"
args="load plugin_lecture/plugin_nodelet_listener $(arg manager_name)" >
<remap from="chatter" to="chatter_alt" />
</node>
</launch>
ビルド
cd ~/catkin_ws
catkin_make
実行
各ターミナルごとに実行前にsource ~/catkin_ws/devel/setup.bash
を実行する必要があります。
roslaunch plugin_lecture nodelet_pubsub.launch
以下のような出力になります。
[ INFO] [1556704402.696000510]: Initializing nodelet with 4 worker threads.
[ INFO] [1556704402.878049806]: Talker Init /node_loader0
[ INFO] [1556704402.886763259]: Listener Constructor
[ INFO] [1556704402.886827535]: Listener Init
[ INFO] [1556704403.881021963]: send: hello2
[ INFO] [1556704403.881770658]: recieve: hello2
[ INFO] [1556704404.881586730]: send: hello2
[ INFO] [1556704404.881755524]: recieve: hello2
[ INFO] [1556704405.881102764]: send: hello2
[ INFO] [1556704405.881328273]: recieve: hello2
nodelet pluginの一覧
システムとして認識しているnodeletのpluginの一覧をみれます。上のコマンドではnodelet plugin用のdescriptionファイルの一覧が見えます。下のコマンドではもっと詳しくclassの単位の一覧をみれます。
rospack plugins --attrib=plugin nodelet
rosrun nodelet declared_nodelets