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

Create an array of subscribers in ROS 2

asked 2022-10-07 04:06:41 -0600

Edvard gravatar image

updated 2022-10-07 05:08:39 -0600

ravijoshi gravatar image

Hello. Sorry for all mistakes. English is not my native tongue. In ROS 1, I have code that looks something like this:

std::vector<ros::Subscriber> sub_sensors_front;

void EnableSensors(bool enable)
{
  if (enable)
  {
    sub_sensors_front = {
      pNodeHandle->subscribe("/minicar/sensor/front_0", 10, SensorInput),
      pNodeHandle->subscribe("/minicar/sensor/front_1", 10, SensorInput),
      pNodeHandle->subscribe("/minicar/sensor/front_2", 10, SensorInput),
      pNodeHandle->subscribe("/minicar/sensor/front_3", 10, SensorInput),
      pNodeHandle->subscribe("/minicar/sensor/front_4", 10, SensorInput),
    };
  }
}

It is working fine. Now I need to migrate my code to ROS 2 foxy, and I am stuck. All I could achieve looks like this, and it is not working.

std::vector<rclcpp::Subscription<sensor_msg::msg::Range>> sub_sensors_front;

void EnableSensors(bool enable)
{
  if (enable)
  {
    sub_sensors_front = {
      pNodeHandle->create_subscription<sensor_msg::msg::Range>("/minicar/sensor/front_0", 10, SensorInput),
      pNodeHandle->create_subscription<sensor_msg::msg::Range>("/minicar/sensor/front_1", 10, SensorInput),
      pNodeHandle->create_subscription<sensor_msg::msg::Range>("/minicar/sensor/front_2", 10, SensorInput),
      pNodeHandle->create_subscription<sensor_msg::msg::Range>("/minicar/sensor/front_3", 10, SensorInput),
      pNodeHandle->create_subscription<sensor_msg::msg::Range>("/minicar/sensor/front_4", 10, SensorInput),
    };
  }
}

VS code following error:

no operator '=' matches these operands

I would appreciate all possible help. If there is a working example, I would be very grateful for it.

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
1

answered 2022-10-07 04:53:10 -0600

ravijoshi gravatar image

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.

edit flag offensive delete link more

Comments

1

Thank you for quick and detailed answer! I'l try this

Edvard gravatar image Edvard  ( 2022-10-07 07:00:39 -0600 )edit
1

I saw the "closed" tag with the following message: Closed for the following reason the question is answered, right answer was accepted by Edvard. close date 2022-10-07 07:00:52.174342

@Edvard: The correct way to accept an answer is mentioned below:

  1. First, upvote the answer. Please click on the ^ icon at the top left side of this answer to do this.
  2. Next, please click on the check mark symbol, ✔ icon, located at the top left side of this answer.

Thank you for your kind cooperation. I believe it is a good practice to follow the rules in an online forum. Thanks!

ravijoshi gravatar image ravijoshi  ( 2022-10-07 22:21:13 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2022-10-07 04:06:41 -0600

Seen: 652 times

Last updated: Oct 07 '22