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

TimeSynchronizer Callback problem

asked 2013-04-17 00:41:22 -0500

Waterplant gravatar image

updated 2014-01-28 17:16:13 -0500

ngrennan gravatar image

I have a problem using the TimeSynchronizer.

I added sub1 and sub2 to test if there is a with the subscriber, but in both cases the callbacks test_callback and test_callback2 are called. Only the synchronized callback is not called.

Thank you very much.

Here is the main part:

ros::Subscriber sub1 = nh.subscribe("/camera/rgb/image_rect_color", 1, test_callback);
ros::Subscriber sub2 = nh.subscribe("/camera/depth_registered/image_rect", 1, test_callback2);

message_filters::Subscriber<sensor_msgs::Image> image_sub(nh, "/camera/rgb/image_rect_color", 1);
message_filters::Subscriber<sensor_msgs::Image> depth_sub(nh, "/camera/depth_registered/image_rect", 1);

TimeSynchronizer<sensor_msgs::Image, sensor_msgs::Image> sync(image_sub, depth_sub, 10);
sync.registerCallback(boost::bind(&callback, _1, _2));
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
11

answered 2013-04-17 02:17:22 -0500

updated 2013-04-17 02:22:06 -0500

The TimeSynchronizer will only work when the timestamps are exactly equal. You need to use the ApproximateTimeSyncronizer: Example (copied from rgbdslam):

typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, 
                                                        sensor_msgs::Image,
                                                        sensor_msgs::CameraInfo> NoCloudSyncPolicy;

class MyClass {
message_filters::Subscriber<sensor_msgs::Image> *visua_sub_;      
message_filters::Subscriber<sensor_msgs::Image> *depth_sub_;      
message_filters::Subscriber<sensor_msgs::CameraInfo> *cinfo_sub_;      
message_filters::Synchronizer<NoCloudSyncPolicy>* no_cloud_sync_;

// method definitions needed here
}

void MyClass::init()
{
std::string visua_tpc("/topic_image_mono");
std::string depth_tpc("/topic_image_depth");
std::string cinfo_tpc("/camera_info_topic");
int q = 5; //queue size
ros::NodeHandle nh;

visua_sub_ = new image_sub_type(nh, visua_tpc, q);
depth_sub_ = new image_sub_type(nh, depth_tpc, q);
cinfo_sub_ = new cinfo_sub_type(nh, cinfo_tpc, q);

no_cloud_sync_ = new message_filters::Synchronizer<NoCloudSyncPolicy>(NoCloudSyncPolicy(q),  *visua_sub_, *depth_sub_, *cinfo_sub_);

no_cloud_sync_->registerCallback(boost::bind(&MyClass::callbackMethod, this, _1, _2, _3));
}

//The callback method
void MyClass::callbackMethod (const sensor_msgs::ImageConstPtr& visual_img_msg,
                              const sensor_msgs::ImageConstPtr& depth_img_msg,
                              const sensor_msgs::CameraInfoConstPtr& cam_info_msg) 
{
     //Your processing code
}
edit flag offensive delete link more

Comments

Thank you very much. That sounds logic

Waterplant gravatar image Waterplant  ( 2013-04-18 20:52:46 -0500 )edit
4

I found this helpful, but linking to original source would be even more helpful as the typedefs for image_sub_type and cinfo_sub_type are missing ( https://github.com/felixendres/rgbdsl... ).

vkee gravatar image vkee  ( 2016-06-28 12:51:57 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2013-04-17 00:41:22 -0500

Seen: 11,629 times

Last updated: Apr 18 '13