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

use cases for tf::MessageFilter::setTolerance [closed]

asked 2015-09-10 10:01:52 -0500

ingo gravatar image

As currently implemented, this method has the effect that canTransform is being invoked with the exact timestamp, and with a timestamp that is "duration" later. So, it's not a tolerance in the sense that anything within that range would be okay, but it ensures that the transform is valid for the full range.

In a situation where there is no tf post-dating, the effect of such a setting will be that the callback of the MessageFilter is delayed until sensor_time+tolerance_duration. This is obvious, because if the transform has any dynamic links, it can't be known prior to that time.

However, it does mean that sensor data will be processed later than it could otherwise have been.

I'm wondering what the rationale for such a function is? When is this necessary, and could it be solved without having to wait until duration expires?

edit retag flag offensive reopen merge delete

Closed for the following reason the question is answered, right answer was accepted by ingo
close date 2015-09-11 02:16:08.003112

1 Answer

Sort by ยป oldest newest most voted
2

answered 2015-09-10 11:52:36 -0500

tfoote gravatar image

The purpose of this call is to support sensor data which does not represent information from exactly one time.

The most common use case for this is the laser scan message. You'll note in it's definition there is a time increment between readings. The timestamp in the header is for the first ray, and every other measurement is offset in time from that first measurement by the time_increment. This level of time accuracy is important for lasers mounted on on moving platforms, such as a nodding laser. The transform for the first ray vs the last ray can be notably different. Because of this you need to be able look up the transform at every time in the range of the measurements.

With the default message_filter behavior you will get a callback when the first ray is available for transform, but since the message filter does not know about the inherent duration of the message's data it will give you the callback right away. And if you try to project the laser scan into a point cloud using the high fidelity API it will throw an exception most times since you don't have transform data for the whole scan. The solution is to tell the message filter to hold the data for the expected additional duration of the message data using the setTolerance method.

For an example usage see this tutorial

edit flag offensive delete link more

Comments

Ah! Thanks a lot for the explanation, now I get it. That means that in reality there won't be any additional delay, because the time of stamp+duration will already have passed once the LaserScan arrives. In my case, I was running tests in simulation. I guess I'll have to fix the simulator then ;-)

ingo gravatar image ingo  ( 2015-09-10 14:12:18 -0500 )edit

oh, btw, would you consider the following use of setTolerance to be valid? https://github.com/ros-planning/navig... It sets a fixed tolerance of 50ms. That can't be appropriate?

ingo gravatar image ingo  ( 2015-09-10 14:14:45 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2015-09-10 10:01:52 -0500

Seen: 458 times

Last updated: Sep 10 '15