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

callback for two topics at the same time

asked 2012-11-03 11:06:19 -0500

dinamex gravatar image

updated 2012-11-03 11:07:57 -0500

Hi everyone,

I would like to save an image from a depthcamera and a webcam at the same time as a mouse click. So I subscribed to the depth image and in this callback I used

 webcam_image = ros::topic::waitForMessage<Image>("/logitech_usb_webcam/image_raw");

but it seems that the wait for message skips the first message and uses the second one instead...

So I went on and tried another solution. Therefore, I used the registerCallback function from the message_filter package but it doesn't behave like I want it because the callback gets never triggered (both topics are published).

My code looks like this

#include <ros/ros.h>
#include <std_msgs/String.h>
#include <message_filters/subscriber.h>
#include <message_filters/time_synchronizer.h>
#include <sensor_msgs/Image.h>


using namespace sensor_msgs;
using namespace message_filters;


void sync_callback(const ImageConstPtr& depth_image, const ImageConstPtr&  webcam_image){

        ROS_INFO("syncro callback");
}



int main(int argc, char **argv){

        ros::init(argc, argv, "listener");
        ros::NodeHandle nh;

        message_filters::Subscriber<Image> depth_sub(nh, "/camera/depth/image", 1);
        message_filters::Subscriber<Image> webcam_sub(nh, "/logitech_usb_webcam/image_raw", 1);
        TimeSynchronizer<Image, Image> sync(depth_sub, webcam_sub, 50);
        sync.registerCallback(boost::bind(&sync_callback, _1, _2));



        ros::spin();
        return 0;
}

Would be great to get your help to get this working.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
8

answered 2012-11-03 14:14:25 -0500

Eric Perko gravatar image

The TimeSynchronizer requires that the timestamps in the messages to be synchronized match exactly. Since you are trying to sync images from two separate cameras that, based on the topic names, are likely not synchronized, their timestamps will not match perfectly. That is why you never get any synchronized image callbacks.

Take a look at http://www.ros.org/wiki/message_filters#ApproximateTime_Policy for approximate time synchronization.

edit flag offensive delete link more

Comments

1

A similar node that works is at http://ibotics.ucsd.edu/trac/stingray/browser/trunk/sync_images, where I used the approximate time synchronizer that Eric referenced.

Thomas D gravatar image Thomas D  ( 2012-11-04 04:58:50 -0500 )edit

thanks a lot to both of you for the good advice...

dinamex gravatar image dinamex  ( 2012-11-04 11:14:11 -0500 )edit

Question Tools

Stats

Asked: 2012-11-03 11:06:19 -0500

Seen: 9,716 times

Last updated: Nov 03 '12