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

Revision history [back]

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;


message_filters::Subscriber<sensor_msgs::Image> *visua_sub_;      
message_filters::Subscriber<sensor_msgs::Image> *depth_sub_;      
message_filters::Subscriber<sensor_msgs::CameraInfo> *cinfo_sub_;      

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);

message_filters::Synchronizer<NoCloudSyncPolicy>* no_cloud_sync_;
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) 
{

}

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);

message_filters::Synchronizer<NoCloudSyncPolicy>* no_cloud_sync_;
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
}