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

How to match messages coming from several nodes to be able to cross-reference data based on timestamps?

asked 2019-12-15 07:01:04 -0500

endrju gravatar image

updated 2019-12-15 11:16:05 -0500

Hello, I was wondering whether it is possible to cache two synced messages with message_filters API in Melodic?

I got two synced messages:

using namespace sensor_msgs; 
message_filters::Subscriber<Image> depth_sub(nodeHandle, "/camera/depth/image_raw", 1);      
message_filters::Subscriber<LaserScan> laser_sub(nodeHandle, "/scan", 1);                    
message_filters::TimeSynchronizer<Image, LaserScan> sync(depth_sub, laser_sub, 10);

And I tried to cache it:

message_filters::Cache< <Image, LaserScan>> cache(sync, 20);

But it didn't work:

 /home/alfierra/catkin_ws/src/distance_estimator/src/DistanceEstimator.cpp:11:46: error: template argument 1 is invalid message_filters::Cache< <Image, LaserScan>> cache(sync, 20);

Is there any way to achieve that? Example code to reproduce:

#include <message_filters/subscriber.h>
#include <message_filters/cache.h>
#include <message_filters/time_synchronizer.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/CameraInfo.h>

using namespace sensor_msgs;
using namespace message_filters;

void callback(const ImageConstPtr& image, const CameraInfoConstPtr& cam_info)
{
  // Solve all of perception here...
}

int main(int argc, char** argv)
{
  ros::init(argc, argv, "vision_node");

  ros::NodeHandle nh;

  message_filters::Subscriber<Image> image_sub(nh, "image", 1);
  message_filters::Subscriber<CameraInfo> info_sub(nh, "camera_info", 1);
  TimeSynchronizer<Image, CameraInfo> sync(image_sub, info_sub, 10);

  // my attempt 
  Cache< <Image, LaserScan>> cache(sync, 20);  

  ros::spin();

  return 0;
}

EDIT:

To avoid an xy-problem, could you please explain to readers here why you want to do this?

I'm implementing a package for a robot equipped with a LIDAR and RGBD camera. The robot is supposed to detect objects (chair, person, etc) and estimate the distance to them. The task of the first node is to analyze camera feed, detect objects and publish relevant information (class label and coords of rectangle that encloses the object). The second node's task is to estimate distance to each of detected objects. It subscribes to the first node but it also needs sensor information (Lidar scan and RBGD image) in order to estimate distance. That's why I need a Cache: to be able to store sensor data and retrieve a sample that corresponds to the timestamp of analyzed image.

I thought that synchronizing laserScan and RGBDImage msgs and caching them would be an elegant solution. Although if it's not supported, I'll just cache them independently.

edit retag flag offensive close merge delete

Comments

1

To avoid an xy-problem, could you please explain to readers here why you want to do this?

gvdhoorn gravatar image gvdhoorn  ( 2019-12-15 07:35:33 -0500 )edit

Thanks, I edited the post.

endrju gravatar image endrju  ( 2019-12-15 09:01:27 -0500 )edit

It would seem this is an xy-problem: you'd like to be able to match messages coming from several nodes to be able to cross-reference data based on timestamps.

Your question title does not reflect this.

You may want to update it.

gvdhoorn gravatar image gvdhoorn  ( 2019-12-15 10:33:15 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2019-12-15 10:24:09 -0500

gvdhoorn gravatar image

The second node's task is to estimate distance to each of detected objects. It subscribes to the first node but it also needs sensor information (Lidar scan and RBGD image) in order to estimate distance. That's why I need a Cache: to be able to store sensor data and retrieve a sample that corresponds to the timestamp of analyzed image.

So if I understand you correctly, you have:

  • node 1: takes in camera image, outputs (a list of) detected/identified objects
  • node 2: takes in laserscan, rgbd and (lists of) detected/identified objects, outputs: estimated distances

if this is correct, wouldn't it make sense to:

  • have node 1 publish its messages with the timestamp of the incoming image (in which the objects were detected)
  • have node 2 synch all three topics (ie: laserscan, rgbd and (lists of) detected/identified objects) and always process the three-tuple?

No Cache needed, and you still have access to the LaserScan and RGBD data which corresponds to the RGB image's stamps in which the objects were detected.


The main point here is: if processing sensor data, think carefully about which timestamp you should associate with the results of that processing. For things like object recognition based on images (or laserscans, lidar, pointclouds, whatever) it's often desirable to associate the timestamp of the original sensor data with the output, as it allows matching the objects with other sensor data captured at the same time.

edit flag offensive delete link more

Comments

You understood correctly. Your solution is much simpler - although won't the delay be a problem here? Camera outputs ~90 fps, lidar publishes ~40 scans per second. The first node with my current setup is capable of analyzing ~15 fps (it doesn't buffer any frames, always takes the most recent one). Is TimeSynchronizer able to synchronize msgs that are so desynchronized? (15fps -> ~66ms of delay). Okey while I was writing this I thought I may as well check the docs -> the queue size is parameterized. This one I missed previously ;) Thanks for help!

endrju gravatar image endrju  ( 2019-12-15 11:06:45 -0500 )edit

Okey while I was writing this I thought I may as well check the docs -> the queue size is parameterized.

you'll indeed need to make sure your message_filter has a sufficiently long queue.

But with a plain Cache you'd have the same requirement.

gvdhoorn gravatar image gvdhoorn  ( 2019-12-15 11:40:47 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2019-12-15 07:01:04 -0500

Seen: 442 times

Last updated: Dec 15 '19