【ROS2関係トップページへ】
【ROS2レクチャー:初級 -class style-】
【前:ROS2における時間管理・Rate系とTimer系】
【次:ROS2独自メッセージの作成】
publisherプログラムを作成する.
メッセージ受信者はここで作成したsubscriberプログラムを使用する.
準備
$ cd ~/ros2_studies_ws/
$ ros2 pkg create minimal_publisher_class --dependencies rclcpp example_interfaces
クラス化したpublisher
作成物:
- src/minimal_publisher.hpp
- src/minimal_publisher.cpp
- src/minimal_publisher_main.cpp
プログラム:src/minimal_publisher.hpp
#include <rclcpp/rclcpp.hpp>
#include <example_interfaces/msg/string.hpp>
class MinimalPublisher : public rclcpp::Node{
private:
rclcpp::Publisher<example_interfaces::msg::String>::SharedPtr publisher_;
rclcpp::TimerBase::SharedPtr timer_;
size_t count_;
public:
MinimalPublisher(
const std::string& name_space="",
const rclcpp::NodeOptions& options = rclcpp::NodeOptions()
);
};
概要
実行に必要な以下の要素と実際の準備・設定を行うコンストラクタの宣言,
- Publisher<メッセージ型>のポインタ
- Timer系での定期実行のためのTimerBase型のポインタ
- 何回目のメッセージかを表すためのcount_
説明
Timer系はTimerBase型となる.詳しくは公式のAPIのTimerの項を参照.
count_はint型でも良いが,非負であればsize_t推奨.特に,配列のインデックスやforのカウンタ.
プログラム:src/minimal_publisher.cpp
#include <rclcpp/rclcpp.hpp>
#include <rclcpp/qos.hpp>
#include <example_interfaces/msg/string.hpp>
#include "minimal_publisher.hpp"
using namespace std::chrono_literals;
MinimalPublisher::MinimalPublisher(
const std::string& name_space,
const rclcpp::NodeOptions& options
): Node("minimal_publisher",name_space,options), count_(0){
publisher_ = this->create_publisher<example_interfaces::msg::String>("topic_test",rclcpp::QoS(10));
timer_ = this->create_wall_timer(
500ms,
[this](){
auto msg = std::make_shared<example_interfaces::msg::String>();
msg->data = "Hello " + std::to_string(count_++);
RCLCPP_INFO(this->get_logger(), "Pub:%s", msg->data.c_str());
publisher_->publish(*msg);
}
);
}
概要
コンストラクタの中で,publisherとして設定しTimerを使用して定期処理を行う.
説明
12行目でpublisherとして設定している.
13行目からがTimerの設定で,create_wall_timer関数を使用する.第一引数が実行周期で今回は500ms.第二引数(15~20行目)が定期的に実行するcallback関数の指定.今回はlambda関数によって実装.メッセージを「発信する側」であり受け取る側でないのでcallback関数には引数がない.また[this]とすることでクラスのメンバ変数(publisher_, count_)にアクセスできるようにしている.
プログラム:src/minimal_publisher_main.cpp
#include <rclcpp/rclcpp.hpp>
#include "minimal_publisher.hpp"
int main(int argc, char * argv[]){
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalPublisher>());
rclcpp::shutdown();
return 0;
}
概要
spin関数のところでクラスを実体化.Timer系のcallback関数の実行.
package.xmlとCMakeLists
以下は追加したところに関係する部分のみを抜粋.
package.xml
<package format="3">
<depend>rclcpp</depend>
<depend>example_interfaces</depend>
CMakeLists.txt
find_package(rclcpp REQUIRED)
find_package(example_interfaces REQUIRED)
add_executable(minimal_publisher_test
src/minimal_publisher_main.cpp
src/minimal_publisher.cpp
)
ament_target_dependencies(minimal_publisher_test
rclcpp
example_interfaces
)
install(TARGETS
minimal_publisher_test
DESTINATION lib/${PROJECT_NAME}
)
ビルド・実行
publisherはここで作成したもの,subscriberはここで作成したものを使用.
ビルド
$ cd ~/ros2_studies_ws/
$ colcon build --symlink-install --packages-up-to minimal_publisher_class
$ . install/local_setup.bash
実行
publisher用のterminalとsubscriber用のterminalを起動.
$ cd ~/ros2_studies_ws/
$ . install/local_setup.bash
$ ros2 run minimal_publisher_class minimal_publisher_test
$ cd ~/ros2_studies_ws/
$ . install/local_setup.bash
$ ros2 run minimal_subscriber_class_node callback_subscriber_test