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

Synchronizer and image_transport::Subscriber

asked 2011-04-12 01:17:11 -0600

Enrique gravatar image

Does message_filters::Synchronizer< POLICY > support image_transport::Subscriber?

As far as I've tried, it only supports message_filters::Subscriber, which is what I'm using now (following http://www.ros.org/wiki/message_filters ).

Probably, using image_transport::Subscriber doesn't bring any advantage over message_filters::Subscriber!?

edit retag flag offensive close merge delete

Comments

So, if I understand well, what you want to do is change the synchronization policy for a image_transport::Subscriber. Is that right?
raphael favier gravatar image raphael favier  ( 2011-04-12 03:23:10 -0600 )edit
No. I'll give an example: I've two image_transport::Publisher in one node, so in another node I want to get those images synchronized. I've found that if you use image_transport::Subscriber, you cannot use message_filters::Synchronizer or any similar. Sorry if I've not explained well.
Enrique gravatar image Enrique  ( 2011-04-12 07:48:56 -0600 )edit
I see. You want to synchronize two image topics. I never tried that so I cannot be really helpful here. Check http://answers.ros.org/question/226/how-to-synchronize-tfmessage-and-image-messages?comment=1455#comment-1455, especially Patrick's comment. Maybe it will help. Can you post your solution if you find one?
raphael favier gravatar image raphael favier  ( 2011-04-15 03:33:56 -0600 )edit
Yes, it seems to be the way to do it. I'll follow the API (http://www.ros.org/doc/api/image_transport/html/classimage__transport_1_1SubscriberFilter.html), and post the solution if it works. Thanks for the hint!
Enrique gravatar image Enrique  ( 2011-04-15 07:10:46 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
19

answered 2011-04-16 01:40:32 -0600

Enrique gravatar image

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.

edit flag offensive delete link more

Comments

Please, mark as answered if you find it correct. Otherwise, let me know and I'll try to check and fix the problem. Thanks all!
Enrique gravatar image Enrique  ( 2011-04-16 01:47:59 -0600 )edit
2

This works. Note that, as I realized first-hand after hours of debugging, it is indeed compulsory to make the sync object a member object, i.e. not a temporary. Otherwise, there is no compilation time error or warning, but your callback never gets called. Even though there is no default constructor.

brice rebsamen gravatar image brice rebsamen  ( 2012-02-28 14:27:56 -0600 )edit
3

If you make it a temporary it gets destroyed when it leaves its context, so there's no longer a callback registered; same happens if you register callbacks for subscribers, or even other stuff like timers.

Enrique gravatar image Enrique  ( 2012-02-28 18:54:40 -0600 )edit

You are missing CameraInfoConstPtr for image_transport right?

tanasis gravatar image tanasis  ( 2017-06-13 08:14:54 -0600 )edit

@tanasis I'm using an image_transport::SubscriberFilter, so it's only for an image, not a camera. You also use a CameraSubscriber, in which case you get the Image and the CameraInfo messages synchronized.

Enrique gravatar image Enrique  ( 2019-03-11 09:17:39 -0600 )edit

Question Tools

4 followers

Stats

Asked: 2011-04-12 01:17:11 -0600

Seen: 14,240 times

Last updated: Apr 16 '11