【ROS2関係トップページへ】
【ROS2レクチャー:初級 -class style-】
【前:ROS2のpublisher/subscriber概要】
【次:ROS2における時間管理・Rate系とTimer系】
クラス化したnodeを用いたsubscriberプログラムを作成する.
ここで作成するプログラムは以下の2種類.一つのパッケージ内で作成.
- クラス化したnodeを使用したsubsciber.callback関数を使用.
- クラス化したnodeを使用したsubsciber.lambda関数を使用.
また,ここではpublisherは作成せず,コマンドでメッセージを送信してsubscriberが受信する様子を観察する.
準備
$ cd ~/ros2_studies_ws/
$ ros2 pkg create minimal_subscriber_class_node --dependencies rclcpp example_interfaces
callback関数を使用したsubscriber
- src/minimal_subscriber.hpp
- subscriber nodeのクラス宣言
- src/minimal_subscriber.cpp
- subscriber nodeのクラス定義
- src/minimal_subscriber_main.cpp
- subscriber nodeを使用した実行ファイル
プログラム:minimal_subscriber.hpp
#include <rclcpp/rclcpp.hpp>
#include <example_interfaces/msg/string.hpp>
class MinimalSubscriber : public rclcpp::Node{
private:
rclcpp::Subscription<example_interfaces::msg::String>::SharedPtr _subscription;
void _topic_callback(const example_interfaces::msg::String::SharedPtr msg);
public:
MinimalSubscriber(
const rclcpp::NodeOptions& options = rclcpp::NodeOptions()
);
MinimalSubscriber(
const std::string& name_space,
const rclcpp::NodeOptions& options = rclcpp::NodeOptions()
);
};
概要
自分のnodeは rclcpp::Nodeからpublic継承して作成.
subscriberとしての設定(トピック名,callback関数との紐付け)を保存する変数_subscriptionをprivateで宣言.
型はrclcpp::Subscription<メッセージ型>でsharedポインタ.
詳しくは公式のAPIのSubscriptionの項を参照.
またcallback関数(関数名:_topic_callback)をprivateで宣言.
プログラム:minimal_subscriber.cpp
#include <rclcpp/rclcpp.hpp>
#include <rclcpp/qos.hpp>
#include <example_interfaces/msg/string.hpp>
#include "minimal_subscriber.hpp"
void MinimalSubscriber::_topic_callback(const example_interfaces::msg::String::SharedPtr msg){
RCLCPP_INFO(this->get_logger(), "I heard: %s", msg->data.c_str());
}
MinimalSubscriber::MinimalSubscriber(
const rclcpp::NodeOptions& options
): MinimalSubscriber("",options){}
MinimalSubscriber::MinimalSubscriber(
const std::string& name_space,
const rclcpp::NodeOptions& options
): Node("minimal_subscriber_test", name_space, options){
_subscription = this->create_subscription<example_interfaces::msg::String>(
"topic_test",
rclcpp::QoS(10),
std::bind(&MinimalSubscriber::_topic_callback, this, std::placeholders::_1)
);
}
概要
nodeが作られるときに準備・設定を行うので,基本的にコンストラクタをいじることになり,14行目からが中心となる.
メッセージを受信したらcallback関数(_topic_callback)を呼んで処理を任せるために,15~19行目で受信設定(subscription)の設定を行っている.
メッセージの種類はとりあえずぱっと使えるexample_interfaceで,その中のstring型(example_interfacesのmsgのstring)を使用.
subscriberのcallback関数はメッセージのポインタを受け取る.
説明
6~8行目:callback関数の定義.subscriberの場合,<>で囲われた型のメッセージ(今回はexample_interfaces::msg::String)を一つ引数として持つ.今回はメッセージを出力するだけの関数.
10行目および14行目からクラスの定義.10行目は結局14行目のコンストラクタに渡されるので,中心は14行目.
17行目:Nodeに"名前"を渡して初期化
18~22行目:subscriberとしての設定.
subscriberとしての設定について
- create_subscription関数で「subscriberとして設定」
- 公式のAPIのSubscriptionの項参照
- subscriberとして(publisherから)受け取るメッセージの種類は<>内で設定
- example_interfaces::msg::String
- 関数の第一引数(19行目)がトピック名の指定
- topic_test
- subscriberがトピックを作るのではなく,publisherが作るトピックの名前を指定
- topic_test
- 関数の第二引数(20行目)はQuality of Serviceの設定
- rclcpp::QoS(n)で「historyをnほど持つ」という意味になるので,適当にnを設定
- rclcpp::QoSの設定自体は様々あるみたいだが,ここではhistoryに関するもののみで「とりあえず」いい?
- 関数の第三引数(21行目)がメッセージを受け取った時の処理・callback関数を指定
- 関数名とその関数に渡す引数を指定するためにstd::bindを使用
- 参考:【C++】std::bindの使い方
- 設定をポインタ変数subscriptionで保存
- subscriptionはautoで型類推しているが,本来はSubscription型のスマートポインタ
\について
[公式APIのQOSの項目](http://docs.ros2.org/foxy/api/rclcpp/classrclcpp_1_1QoS.html)では\となっているが,/opt/ros/foxy/include以下を見ると\が正しそうに見える.APIの記述が変わるか,プログラムの記述を変えなくてはいけなくなるか分からないのでメモROS風と異なるところは以下.
- このクラスによって実体化されたnodeなので,"this"->create_subscriptionとthis(このポインタ)が使用される
- 21行目でcallback関数と紐づけられている.bindの第二引数のthisは,このクラスのメンバ変数・メンバ関数にアクセスできるようにするためのもの.bindの第三引数からcallback関数に引き渡す引数になっている.
- std::bindの参考:【C++】std::bindの使い方
string型について
- 3行目のようにexample_interfaces/msg/string.hppをインクルード.
- string.hppはファイル名
- 使用する場合には,6行目のようにexample_interfaces::msg::Stringと指定
- Stringはクラス名
- メッセージはSharedPtr,UniquePtr,WeakPtrの使用が可
- ros2/example_interfacesを見るとわかるが,example_interfacesのStringクラスはstring型の変数dataのみを持つ.文字列として出力するために8行目のようにc_str()でC言語の文字列に変換している.
プログラム:minimal_subscriber_main.cpp
#include <rclcpp/rclcpp.hpp>
#include "minimal_subscriber.hpp"
int main(int argc, char * argv[]){
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalSubscriber>());
rclcpp::shutdown();
return 0;
}
概要
基本的にnodeを作ってspinに渡せばよい.
そうするとnodeが実体化して,subscriberの役割がオンになる(データ受信待ちとなる).
Nodeでなく,自分で作成したクラスなので,std::make_sharedとなる.
lambda関数を使用したsubsciber
作成物:
- ~/ros2_studies_ws/src/minimal_subscriber_class_node/src/minimal_subscriber_with_lambda.hpp
- subscriber nodeのクラス宣言
- ~/ros2_studies_ws/src/minimal_subscriber_class_node/src/minimal_subscriber_with_lambda.cpp
- subscriber nodeのクラス定義
- ~/ros2_studies_ws/src/minimal_subscriber_class_node/src/minimal_subscriber_main.cpp
- subscriber nodeを使用した実行ファイル
- callback関数を用いたときのmain関数と同じになるので新しく作らず再利用.
プログラム:minimal_subscriber_with_lambda.hpp
#include <rclcpp/rclcpp.hpp>
#include <example_interfaces/msg/string.hpp>
class MinimalSubscriber : public rclcpp::Node{
private:
rclcpp::Subscription<example_interfaces::msg::String>::SharedPtr _subscription;
public:
MinimalSubscriber(
const rclcpp::NodeOptions& options = rclcpp::NodeOptions()
);
MinimalSubscriber(
const std::string& name_space,
const rclcpp::NodeOptions& options = rclcpp::NodeOptions()
);
};
概要
callback関数編との違いは,callback関数がないだけ.
プログラム:minimal_subscriber_with_lambda.cpp
#include <rclcpp/rclcpp.hpp>
#include <rclcpp/qos.hpp>
#include <example_interfaces/msg/string.hpp>
#include "minimal_subscriber_with_lambda.hpp"
MinimalSubscriber::MinimalSubscriber(
const rclcpp::NodeOptions& options
): MinimalSubscriber("",options){}
MinimalSubscriber::MinimalSubscriber(
const std::string& name_space,
const rclcpp::NodeOptions& options
): Node("minimal_subscriber_test", name_space, options){
_subscription = this->create_subscription<example_interfaces::msg::String>(
"topic_test",
rclcpp::QoS(10),
[this](const example_interfaces::msg::String::SharedPtr msg){
RCLCPP_INFO(this->get_logger(), "I heard: %s", msg->data.c_str());
}
);
}
概要
nodeが作られるときに準備・設定を行うので,基本的にコンストラクタをいじることになる.
説明
17行目のようにlambda関数の[]を[this]とし,このクラスのメンバ変数・メンバ関数にアクセスできるようになっている.
プログラム:minimal_subscriber_main.cpp
概要
callback関数の時に作成したものを再利用.
package.xmlとCMakeLists.txt
package.xml
以下は重要な部分のみを抜粋.
<package format="3">
<depend>rclcpp</depend>
<depend>example_interfaces</depend>
説明
rclcppに加え,example_interfacesを使用しているので追加.
CMakeLists.txt
以下は重要な部分のみを抜粋.
find_package(rclcpp REQUIRED)
find_package(example_interfaces REQUIRED)
add_executable(callback_subscriber_test
src/minimal_subscriber_main.cpp
src/minimal_subscriber.cpp
)
ament_target_dependencies(callback_subscriber_test
rclcpp
example_interfaces
)
add_executable(lambda_subscriber_test
src/minimal_subscriber_main.cpp
src/minimal_subscriber_with_lambda.cpp
)
ament_target_dependencies(lambda_subscriber_test
rclcpp
example_interfaces
)
install(TARGETS
callback_subscriber_test
lambda_subscriber_test
DESTINATION lib/${PROJECT_NAME}
)
rclcppに加え,example_interfacesを使用しているので2行目のように指定.
ビルド・実行
ビルド
$ cd ~/ros2_studies_ws/
$ colcon build --symlink-install --packages-up-to minimal_subscriber_class_node
$ . install/local_setup.bash
実行
subscriber(メッセージ受信者)とpublisher(今回はコマンドでメッセージを発信)のため,二つのterminalを起動させる.
$ cd ~/ros2_studies_ws/
$ . install/local_setup.bash
$ ros2 run minimal_subscriber_class_node [ターゲット名]
CMakeLists.txtにあるとおり,ターゲット名は以下の通り.全部やってみよう.
- callback_subscriber_test
- lambda_subscriber_test
$ cd ~/ros2_studies_ws/
$ . install/local_setup.bash
$ ros2 topic pub /topic_test example_interfaces/String '{data: hello}'
下記のコマンドでデータを発信("pub"lication)している.詳しくはROS2の紹介 by gbiggs.
- ros2 topic pub [トピック名] [データの型] [YAML形式で指定したデータ]
補足
$ ros2 node list # ノード一覧が表示される
$ ros2 interface list # メッセージ一覧が表示される
$ ros2 interface show example_interfaces/msg/String # example_interfaces/msg/Stringの構造が表示される
$ ros2 topic list # トピック一覧が表示される
$ ros2 topic pub /topic_test std_msgs/String '{data: hello}'
詳しくはIntrospection with command line toolsもしくはROS2コマンド一覧を参照.
【前:ROS2のpublisher/subscriber概要】
【次:ROS2における時間管理・Rate系とTimer系】