ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

There are following two issues which you should pay attention to:

  1. The callback needs to be attached using std::bind function
  2. The returned value from create_subscription is a shared pointer

An example is shown below:

rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_ = this->create_subscription<std_msgs::msg::String>("topic", 10, std::bind(&MinimalSubscriber::topic_callback, this, _1));

Below is the complete code:

#include <memory>
#include <vector>

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
using std::placeholders::_1;
using MyDataType = std_msgs::msg::String;

class MinimalSubscriber : public rclcpp::Node
{
public:
  MinimalSubscriber() : Node("minimal_subscriber")
  {
    auto fn = std::bind(&MinimalSubscriber::topic_callback, this, _1);
    sub_string_front_ = {
      this->create_subscription<MyDataType>("topic_0", 10, fn),
      this->create_subscription<MyDataType>("topic_1", 10, fn),
      this->create_subscription<MyDataType>("topic_2", 10, fn),
      this->create_subscription<MyDataType>("topic_3", 10, fn),
      this->create_subscription<MyDataType>("topic_4", 10, fn),
    };
  }

private:
  void topic_callback(const MyDataType::SharedPtr msg) const
  {
    RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str());
  }

  std::vector<rclcpp::Subscription<MyDataType>::SharedPtr> sub_string_front_;
};

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

I published string data, and the above code could pick it up, as shown below:

$ ros2 topic pub /topic_0 std_msgs/String "data: this is topic 0"
$ ros2 topic pub /topic_1 std_msgs/String "data: this is topic 1"
$ ros2 topic pub /topic_2 std_msgs/String "data: this is topic 2"
$ ros2 topic pub /topic_3 std_msgs/String "data: this is topic 3"
$ ros2 topic pub /topic_4 std_msgs/String "data: this is topic 4"
$ ros2 run examples_rclcpp_minimal_subscriber subscriber_member_function
[INFO] [1665135719.026351648] [minimal_subscriber]: I heard: 'this is topic 3'
[INFO] [1665135719.111050972] [minimal_subscriber]: I heard: 'this is topic 0'
[INFO] [1665135719.111050972] [minimal_subscriber]: I heard: 'this is topic 1'
[INFO] [1665135719.480602787] [minimal_subscriber]: I heard: 'this is topic 2'
[INFO] [1665135719.495162462] [minimal_subscriber]: I heard: 'this is topic 4'
[INFO] [1665135720.026269129] [minimal_subscriber]: I heard: 'this is topic 3'
[INFO] [1665135720.111080977] [minimal_subscriber]: I heard: 'this is topic 0'

As always, ros2/examples and ros2/demos are your good friend. So feel free to look at them.