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

How to subscribe to two images (ROS 2 and C++)

asked 2020-08-27 21:12:13 -0500

mirella melo gravatar image

updated 2020-08-27 21:16:44 -0500

Hi.

I'm trying to use message_filters package (I also tried with image_transport...) to subscribe to two images. I couldn't understand the usage for ROS 2, but I found this short example for ROS 1. So, what changes do I need to do in this code to have it running in ROS 2?

Thanks in advance.

  using namespace sensor_msgs;
  using namespace message_filters;

  void callback(const ImageConstPtr& image, const ImageConstPtr& cam_info)
  {
       // Callback function...
  }

  int main(int argc, char** argv)
  {
         ros::init(argc, argv, "vision_node");
         ros::NodeHandle nh;

         message_filters::Subscriber<Image> image_1(nh, "image_1", 1);
         message_filters::Subscriber<Image> image_2(nh, "image_2", 1);
         TimeSynchronizer<Image, Image> sync(image_sub, info_sub, 10);
         sync.registerCallback(boost::bind(&callback, _1, _2));

        ros::spin();

        return 0;
  }
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2020-08-27 23:30:51 -0500

mirella melo gravatar image

updated 2020-09-06 13:40:59 -0500

I finally found the equivalent...

 #include "rclcpp/rclcpp.hpp"
 #include "sensor_msgs/msg/image.hpp"
 #include <message_filters/subscriber.h>
 #include <message_filters/synchronizer.h>
 #include <message_filters/sync_policies/approximate_time.h>
 #include <message_filters/time_synchronizer.h>
 #include "boost/bind/bind.hpp"

void callback(const sensor_msgs::msg::Image::ConstSharedPtr& left, const     
       sensor_msgs::msg::Image::ConstSharedPtr& right) {
    // Callback function...
}

int main(int argc, char** argv){
    rclcpp::init(argc, argv);
    auto node = rclcpp::Node::make_shared("my_node");

    message_filters::Subscriber<sensor_msgs::msg::Image> image_1(node, "image_1");
    message_filters::Subscriber<sensor_msgs::msg::Image> image_2(node, "image_2");
    message_filters::TimeSynchronizer<sensor_msgs::msg::Image, sensor_msgs::msg::Image> sync(image_1, image_2, 10);
    sync.registerCallback(boost::bind(&callback, boost::placeholders::_1, boost::placeholders::_2));
    rclcpp::spin(node);
    return 0;
}
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2020-08-27 21:12:13 -0500

Seen: 1,984 times

Last updated: Sep 06 '20