Re: [ros-users] problem using TimeSynchronizer with two imag…

Top Page
Attachments:
Message as email
+ (text/plain)
+ (text/html)
+ stereo_subscriber.cpp (text/x-c++src)
Delete this message
Reply to this message
Author: Patrick Mihelich
Date:  
To: ros-users
Subject: Re: [ros-users] problem using TimeSynchronizer with two images
Hi Dan,

You might need to increase the size of the queues used by the subscriber
filters and/or the synchronizer. If those queues fill up, messages can get
bumped off before they form a complete synchronized set.

For debugging purposes it can be useful to register another callback to the
subscriber filters, just so you know when they get any data. I've attached
some sample source code.

"compressed" transport definitely should work with the time synchronizer.
"theora" will not work reliably because it seems the plugin doesn't retain
the timestamp of the original image. I've opened a
ticket<https://code.ros.org/trac/ros-pkg/ticket/3882>for that.

HTH,
Patrick

On Fri, Mar 12, 2010 at 9:12 AM, Dan Lazewatsky
<>wrote:

> Thanks, that did the trick. One thing I'm still having trouble with is
> getting transports other than raw to work with
> image_transport::SubscriberFilter. If I pass image_transport::TransportHints
> th(transport) to image_transport::SubscriberFilter, where transport is
> "compressed" or "theora", I never seem to get any data. rxgraph -t shows
> that my node is connected to my image publisher on the right topic, but the
> callback never gets called.
>
> Thanks,
> -Dan
>
>
> On 3/11/10 5:11 PM, Patrick Mihelich wrote:
>
> On Thu, Mar 11, 2010 at 2:55 PM, Dan Lazewatsky <
> > wrote:
>
>> On a related note, is there a way to use TimeSynchronizer with
>> image_transport rather than subscribing to the image directly?
>>
>
> Use image_transport::SubscriberFilter<http://www.ros.org/doc/api/image_transport/html/classimage__transport_1_1SubscriberFilter.html>as a drop-in replacement for message_filters::Subscriber. It uses an
> image_transport subscriber under the hood.
>
> Cheers,
> Patrick
>
>
> _______________________________________________
> ros-users mailing list
> https://code.ros.org/mailman/listinfo/ros-users
>
>
> _______________________________________________
> ros-users mailing list
>
> https://code.ros.org/mailman/listinfo/ros-users
>
>

#include <ros/ros.h>
#include <image_transport/image_transport.h>
#include <image_transport/subscriber_filter.h>
#include <opencv/cv.h>
#include <opencv/highgui.h>
#include <cv_bridge/CvBridge.h>
#include <message_filters/time_synchronizer.h>

sensor_msgs::CvBridge left_bridge, right_bridge;

void monoCallback(const sensor_msgs::ImageConstPtr& msg, const std::string& side)
{
ROS_INFO("%s image received, stamp %f", side.c_str(), msg->header.stamp.toSec());
}

void stereoCallback(const sensor_msgs::ImageConstPtr& left, const sensor_msgs::ImageConstPtr& right)
{
  ROS_INFO("Stereo callback invoked");
  try
  {
    cvShowImage("left", left_bridge.imgMsgToCv(left, "bgr8"));
    cvShowImage("right", right_bridge.imgMsgToCv(right, "bgr8"));
  }
  catch (sensor_msgs::CvBridgeException& e)
  {
    ROS_ERROR("Conversion failed. Left encoding = [%s], right encoding = [%s].",
              left->encoding.c_str(), right->encoding.c_str());
  }
}


int main(int argc, char **argv)
{
ros::init(argc, argv, "stereo_listener");
ros::NodeHandle nh;

cvNamedWindow("left");
cvNamedWindow("right");
cvStartWindowThread();

image_transport::ImageTransport it(nh);
image_transport::TransportHints hints("raw", ros::TransportHints().udp());
image_transport::SubscriberFilter sub_l, sub_r;
sub_l.subscribe(it, "left_image", 3, hints);
sub_r.subscribe(it, "right_image", 3, hints);
message_filters::TimeSynchronizer<sensor_msgs::Image, sensor_msgs::Image> sync(sub_l, sub_r, 3);
sync.registerCallback(stereoCallback);
sub_l.registerCallback(boost::bind(monoCallback, _1, "left"));
sub_r.registerCallback(boost::bind(monoCallback, _1, "right"));

ros::spin();

cvDestroyWindow("left");
cvDestroyWindow("right");
}