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

How can I subscribe to 2 different topics in a synchronised manner in ROS2 ?

asked 2018-05-22 05:15:57 -0500

aks gravatar image

I have 3 different nodes : Node2 subscribes to two different topics of same types published by node 1 and node3. Then it does some calculations on these subscribed topics and the publishes to a new topic which is then subscribed by node 3. So basically I want to test looping calculations.

Here is my class definition for node2 which is subscribing to 1 topic and publishing to 1 :

    class HeatConduction1 : public rclcpp::Node
{
public:
  explicit HeatConduction1(const std::string & topic_subscriber1,const std::string & topic_publisher)
  : Node("heatConduction1")
  {


    auto callback =
      [this](const std_msgs::msg::Float32::SharedPtr msg_) -> void
      {

    heatflow = calculateHeatFlow(heatflow,tempPM1,msg_->data);
    tempPM1 = calculateTempPM1(tempPM1, msg_->data,heatflow);



    RCLCPP_INFO(this->get_logger(), "I heard from source node the source heatflow: [%f]", msg_->data)
    //RCLCPP_INFO(this->get_logger(), "I heard from heatconduction2 node as the tempPM2: [%f]", msg_2->data)


    pub_msg = std::make_shared<std_msgs::msg::Float32>();

    pub_msg->data = tempPM1;
    RCLCPP_INFO(this->get_logger(), "Publishing: '%f'", pub_msg->data)
    pub_->publish(pub_msg);
      };


    sub_ = create_subscription<std_msgs::msg::Float32>(topic_subscriber1, callback);
   // sub_1 = create_subscription<std_msgs::msg::Float32>(topic_subscriber2, callback);

    pub_ = this->create_publisher<std_msgs::msg::Float32>(topic_publisher, rmw_qos_profile_default);

   }

Now, how can i modify this code to add another subscriber. Can I pass another argument in the constructor naming const std::string & topic_subscriber2 and then create another shared pointer as sub_1 and use a callback command as sub_1 = create_subscription<std_msgs::msg::Float32>(topic_subscriber2, callback); But this is not working as it gives a compilation error.

Or should i have another callback function in the constructor and call it seperately ? but in this case how would the callbacks be synchronised ?

Any helps would be appreciated.

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
2

answered 2019-07-25 05:22:50 -0500

alsora gravatar image

updated 2019-07-25 05:23:55 -0500

You have to use the message_filter package.

Among the other things, this allows you to create synchronized callbacks. You can use it to define callbacks which takes more than 1 message as argument. Note that all messages must have an header field with the timestamp.

void sync_callback(const StampedStringMsg::SharedPtr string_msg, const StampedBooleanMsg::SharedPtr bool_msg)
{
  std::cout<<"Received msg: "<< string_msg->data<< " and msg " << bool_msg->data<<std::endl;
}

You need to choose a synchronization strategy: exact or approximate. The first one will require that both messages have the exact same timestamp in order for the callback to be triggered. The other will use heuristics to try to match messages with slightly different timestamps.

  // create subscribers to the topics of interest
  message_filters::Subscriber<StampedStringMsg> string_sub(node, "stamped_string_topic", qos_profile);
  message_filters::Subscriber<StampedBooleanMsg> bool_sub(node, "stamped_boolean_topic", qos_profile);

  // exact time policy
  typedef message_filters::sync_policies::ExactTime<StampedStringMsg, StampedBooleanMsg> exact_policy;
  message_filters::Synchronizer<exact_policy>syncExact(exact_policy(10), string_sub, bool_sub);

  // register the exact time callback
  syncExact.registerCallback(sync_callback);

You can find a full working example here https://github.com/alsora/ros2-code-e...

edit flag offensive delete link more
-2

answered 2019-07-24 21:38:52 -0500

jalil gravatar image

You can subscribe another topic by add this command:

sub_1 = this->create_subscription<std_msgs::msg::float32>(topic_subscriber2, callback);

Thank you.

edit flag offensive delete link more

Question Tools

3 followers

Stats

Asked: 2018-05-22 05:15:57 -0500

Seen: 3,995 times

Last updated: Jul 25 '19