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

Revision history [back]

click to hide/show revision 1
initial version

According to Patrick's comment we can use image_transport::SubscriberFilter (see the Code API). Indeed, it's encourage over message_transport::Subscriber< sensor_msgs::Image >. Thanks Raphael, for your help.

In the next code snippet we have a possible implementation. The macro USE_IMAGE_TRANSPORT_SUBSCRIBER_FILTER allows to switch between both approaches.


#include <ros/ros.h>
#include <image_transport/image_transport.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>

#define USE_IMAGE_TRANSPORT_SUBSCRIBER_FILTER 1

#if USE_IMAGE_TRANSPORT_SUBSCRIBER_FILTER
#  include <image_transport/subscriber_filter.h>
#else
#  include <sensor_msgs/Image.h>
#  include <message_filters/subscriber.h>
#endif

class MyClass {
public:
  MyClass() :
    it_(nh_),
#if USE_IMAGE_TRANSPORT_SUBSCRIBER_FILTER
    orig_image_sub_( it_, "image/orig", 1 ),
    warp_image_sub_( it_, "image/warp", 1 ),
#else
    orig_image_sub_( nh_, "image/orig", 1 ),
    warp_image_sub_( nh_, "image/warp", 1 ),
#endif
    sync( MySyncPolicy( 10 ), orig_image_sub_, warp_image_sub_ )
  {
    sync.registerCallback( boost::bind( &MyClass::callback, this, _1, _2 ) );
  }

  void callback(
    const sensor_msgs::ImageConstPtr& orig_msg,
    const sensor_msgs::ImageConstPtr& warp_msg
  ){
    // your code here
  }

private:
  ros::NodeHandle nh_;
  image_transport::ImageTransport it_;

#if USE_IMAGE_TRANSPORT_SUBSCRIBER_FILTER
  typedef image_transport::SubscriberFilter ImageSubscriber;
#else
  typedef message_filters::Subscriber< sensor_msgs::Image > ImageSubscriber;
#endif

  ImageSubscriber orig_image_sub_;
  ImageSubscriber warp_image_sub_;

  typedef message_filters::sync_policies::ApproximateTime<
    sensor_msgs::Image, sensor_msgs::Image
  > MySyncPolicy;

  message_filters::Synchronizer< MySyncPolicy > sync;
};

int main(int argc, char** argv) {
  ros::init( argc, argv, "my_node" );
  MyClass mc;

  while( ros::ok() ){
    ros::spin();
  }

  return EXIT_SUCCESS;
}
 

Note that you can syncrhonize more messages (even of other type) by extending the message_filters::sync_policies::ApproximateTime< ... > template class.