はじめに
Ubuntu18.04のサポート期間終了も近づきつつあったのでROSからROS2へ更新を行いました.
ROS2関連の情報はまだまだ少なく,公式ドキュメントもあまり整備されていません.
今回はC++(rclcpp)において,コールバック関数ではなくwait_for_message
関数を用いてトピックを一度だけ購読してみます.
(トピックの一度限りの購読に関して日本語はおろか英語でも全くと言っていいほど説明しているサイトがなかった.結構需要はあると思うのですが…)
wait_for_messageを用いたトピックの購読
rclcpp::wait_for_messageについての詳しい情報はリンクのドキュメントを参照してください.
以下がwait_for_message
関数を用いた簡単なトピック購読のサンプルコードになります.
サンプルではsensor_msg/Image型のトピックを読み取ります.
#include <rclcpp/rclcpp.hpp>
#include <rclcpp/wait_for_message.hpp>
#include <sensor_msgs/msg/image.hpp>
#include <chrono>
int main(int argc, char* argv[]){
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("subscribe_topic_once");
sensor_msgs::msg::Image image_msg;
std::string topic_name = "sample_topic";
auto timeout = std::chrono::milliseconds(100);
bool is_successful = rclcpp::wait_for_message(image_msg, node, topic_name, timeout);
if(is_successful){
// 購読に成功したときの処理
RCLCPP_INFO(node->get_logger(), "SUCCESS");
}else{
// 購読に失敗したときの処理
RCLCPP_ERROR(node->get_logger(), "FAILURE");
}
return 0;
}
引数は
・第1引数...成功したときに受信メッセージを格納する変数
・第2引数...ノード
・第3引数...購買するトピック名
・第4引数...タイムアウト時間
となります.
タイムアウト時間内に受信に成功すると,image_msgに受信内容がセットされ,関数はtrueを返します.
もしタイムアウト時間内に受信できなかった場合はfalseが返されます.
<<2022/04/18追記>>
ROS2ではrclcpp::Nodeクラスを継承してノードを構築していくことが推奨されています.もしクラスを用いてノードを作る場合wait_for_messageの第2引数にshared_from_this()を入れます.参考サイトはここです.
rclcpp::wait_for_message(image_msg, this->shared_from_this(), topic_name, timeout);
まだ試していませんが,これを使えばwait_for_message以外のNodeへのポインタを引数に必要とする関数も使用できるはずです.