🔦

ROS2プログラミング入門 #8 ノードをクラスにする

2022/05/29に公開

この記事では、ROS2プログラミングでノードをクラスにする方法を紹介します。

はじめに

コールバック関数を使用したサブスクライバーは別にして、これまで作ったプログラムはいずれも main() 関数にすべての処理がありました。

main() 関数はプログラムのエントリーポイントですから、なるべく短い方が良いと思います。

というわけで今回は、ノードをクラスにして main() 関数ではそのインスタンス化だけを行う、ということをやってみましょう。

パブリッシャーとサブスクライバー

以前に作ったパブリッシャー my_publisher.cpp とサブスクライバー my_subscriber.cpp を、クラスを使った形に書き直してみます。

パブリッシャー

まずはパブリッシャーのノードをクラスにするところから始めます。

パブリッシャーのヘッダファイル

ヘッダファイルは次のようにしました。クラス名は SimplePublisher です。

simple_publisher.hpp
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

class SimplePublisher : public rclcpp::Node
{
public:
  SimplePublisher();

private:
  void timer_callback();
  rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
  rclcpp::TimerBase::SharedPtr timer_;
};

以前のものといろいろ違いますけれど、特に2つ大きな違いがあります。

1つ目は、ノードをクラスにするため rclcpp::Node クラスを継承しているということです。この継承は必須になります。

2つ目は、メンバ変数の宣言で具体的な型を使っているということです。この理由は auto による型推論が使えないためです。

また、周期的に呼び出すためのコールバック関数 timer_callback() を宣言しています。

パブリッシャーのソースファイル

ヘッダファイルと対応するソースファイルは次のようになります。

simple_publisher.cpp
#include "my_first_package/simple_publisher.hpp"

SimplePublisher::SimplePublisher() : Node("simple_publisher")
{
  publisher_ = this->create_publisher<std_msgs::msg::String>("greeting", 1);

  using namespace std::chrono_literals;
  timer_ = this->create_wall_timer(1s, std::bind(&SimplePublisher::timer_callback, this));
}

void SimplePublisher::timer_callback()
{
  static int count = 0;
  auto msg = std_msgs::msg::String();
  msg.data = "Hello, world " + std::to_string(count++);
  publisher_->publish(msg);
}

はじめに SimplePublisher のコンストラクタ初期化子で基底クラス Node のコンストラクタを呼び出し、ノード名を指定する必要があります。

publisher_ の初期化は以前と同様ですね。

続く timer_ の初期化では create_wall_timer() 関数を使い、一定間隔で実行されるコールバック関数を登録しています。これで timer_callback() 関数が1秒毎に呼ばれるようになります。

timer_callback() 関数の中身は以前と同様ですね。

パブリッシャーのインスタンス化

パブリッシャーをインスタンス化するソースファイルも必要です。これは次のようになります。

simple_publisher_main.cpp
#include "rclcpp/rclcpp.hpp"
#include "my_first_package/simple_publisher.hpp"

int main(int argc, char **argv)
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<SimplePublisher>());
  rclcpp::shutdown();
  return 0;
}

サブスクライバー

サブスクライバーのノードもクラスにしていきましょう。

サブスクライバーのヘッダファイル

ヘッダファイルは次のようにしました。クラス名は SimpleSubscriber です。

simple_subscriber.hpp
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

class SimpleSubscriber : public rclcpp::Node
{
public:
  SimpleSubscriber();

private:
  void topic_callback(const std_msgs::msg::String::SharedPtr msg) const;
  rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
};

トピックをサブスクライブした時に呼び出すためのコールバック関数 topic_callback() と、サブスクライブを登録するための subscription_ を宣言しています。

サブスクライバーのソースファイル

ヘッダファイルと対応するソースファイルは次のようになります。

simple_subscriber.cpp
#include "my_first_package/simple_subscriber.hpp"

SimpleSubscriber::SimpleSubscriber() : Node("simple_subscriber")
{
  using std::placeholders::_1;
  subscription_ = this->create_subscription<std_msgs::msg::String>("greeting", 1,
    std::bind(&SimpleSubscriber::topic_callback, this, _1));
}

void SimpleSubscriber::topic_callback(const std_msgs::msg::String::SharedPtr msg) const
{
  RCLCPP_INFO(this->get_logger(), "%s", msg->data.c_str());
}

パブリッシャーと同じく、コンストラクタ初期化子で基底クラス Node のコンストラクタを呼び出し、ノード名を指定します。

次の subscription_ の初期化では std::bind()using std::placeholders::_1; といった見慣れないものが登場します。

実はパブリッシャーで timer_ を初期化する時も使っていますが、 std::bind() は引数を束縛した関数オブジェクトを返す関数です。そして、引数の _1bind() のプレースホルダーオブジェクトです。

今のところはクラスを使う際に必要な「おまじない」と思っておいて良いかも知れません。

サブスクライバーのインスタンス化

サブスクライバーをインスタンス化するソースファイルも見ておきます。

simple_subscriber_main.cpp
#include "rclcpp/rclcpp.hpp"
#include "my_first_package/simple_subscriber.hpp"

int main(int argc, char **argv)
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<SimpleSubscriber>());
  rclcpp::shutdown();
  return 0;
}

動作確認

ビルド設定ファイルを編集してビルドし、動作確認を行いましょう。

CMakeLists.txt に次の行を追加して (cd ~/dev_ws/ && colcon build) でビルドします。

unset(NODES)
set(NODES simple_publisher;simple_subscriber)
foreach(target IN LISTS NODES)
  add_executable(${target}_node src/${target}_main.cpp src/${target}.cpp)
  ament_target_dependencies(${target}_node rclcpp std_msgs)
  install(TARGETS ${target}_node DESTINATION lib/${PROJECT_NAME})
  target_include_directories(${target}_node
    PUBLIC
      $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
      $<INSTALL_INTERFACE:include>
  )
endforeach()

ビルドできたらターミナルを2つ起動し、それぞれで次のように実行しましょう。

ros2 run my_first_package simple_subscriber_node
ros2 run my_first_package simple_publisher_node

次のような感じで表示されれば成功です。

simple_subscriber_nodeを実行した様子
simple_subscriber_nodeを実行した様子

simple_publisher_nodeを実行した様子
simple_publisher_nodeを実行した様子

おわりに

今回は、ROS2プログラミングでノードをクラスにする方法を紹介しました。どなたかのお役に立てば幸いです。

Discussion