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

tf wait for transform failure

asked 2012-09-05 09:05:35 -0500

updated 2014-01-28 17:13:34 -0500

ngrennan gravatar image

I believe this question is related to http://answers.ros.org/question/12358/tfwaitfortransform-does-not-wait-for-transform/, though I am not sure if a bug report was filed with the previous one.

I cannot get TransformListener::waitForTransform to wait for the given duration - Unless I supply an excessive long timeout (10000 seconds), the waitForTransform call returns immediately. It also never seems to succeed.

A bag file to reproduce this error is available here (47 MB). To run the bag file, don't use --clock as /clock was recorded explicitly:

rosparam set /use_sim_time true && rosbag play tf.bag

This bag file was recorded for a multi robot setup in simulation, and a number of different nodes are publishing tf information. The view frames output (is correct), and available here. This output can be reproduced by running:

rosrun tf view_frames

On the other hand, while running tf_echo the waitForTransform call in tf_echo always fails, and the first lookupTransform fails (as waitForTransform does not wait sufficiently long). All subsequent lookupTransform calls produce the correct output:

rosrun tf tf_echo /segbot1/base_footprint /segbot1/ens1/map

Example Output:

Failure at 458.729000000
Exception thrown:Frame id /segbot1/base_footprint does not exist! Frames (1): 
The current list of frames is:

At time 459.605
- Translation: [-5.000, -5.000, 0.001]
- Rotation: in Quaternion [0.000, 0.000, -0.000, 1.000]
            in RPY [0.000, 0.000, -0.000]
At time 460.600
- Translation: [-5.000, -5.000, 0.001]
- Rotation: in Quaternion [0.000, 0.000, -0.000, 1.000]
            in RPY [0.000, 0.000, -0.000]

I made a local copy of tf_echo, and increased the wait duration to about 100 seconds. I have an average gazebo speedup between 2.5 to 3.5 seconds, so I should see the waitForTransform call blocking for about 30 seconds before looking up the transform. This does not happen, and the call returns immediately (unsuccessful).

If anyone has any insights into this, then let me know. Otherwise I'll proceed with filing this as a bug. Currently the waitForTransform call for this transform fails repeatedly in a loop in the navigation stack.

UPDATE #1

I have created a simple downloadable package to test tf_echo here.

Usage:

rosrun tf_test tf_echo /segbot1/base_footprint /segbot1/ens1/map _duration:=1.0
rosrun tf_test tf_echo /segbot1/base_footprint /segbot1/ens1/map _duration:=10.0
rosrun tf_test tf_echo /segbot1/base_footprint /segbot1/ens1/map _duration:=100.0

Output:

using duration: 100
waitForTransform Success: 0
Failure at 458.520000000
Exception thrown:Frame id /segbot1/ens1/map does not exist! Frames (5): Frame /segbot1/base_footprint exists with parent /segbot1/odom.
Frame /segbot1/odom exists with parent NO_PARENT.
Frame /segbot2/base_footprint exists with parent /segbot2/odom.
Frame /segbot2/odom exists with parent NO_PARENT.

The current list of frames is:
Frame /segbot1/base_footprint exists with parent /segbot1/odom.
Frame /segbot1/odom exists with parent NO_PARENT.
Frame /segbot2/base_footprint exists with parent /segbot2/odom.
Frame /segbot2/odom exists with parent NO_PARENT.

At time 459.401
- Translation: [-5.000, -5.000, 0.001 ...
(more)
edit retag flag offensive close merge delete

Comments

How do you call waitForTransform? Could you please provide the C++ code snippet you are using?

Lorenz gravatar image Lorenz  ( 2012-09-05 10:23:31 -0500 )edit

@Lorenz: The waitForTransform call is inside the tf/tf_echo node. See https://kforge.ros.org/geometry/geometry/file/b51c3e0a9c70/tf/src/tf_echo.cpp. I made a local copy and changed line 79 to set the duration to 100.0. If you want, I can provide a ready package for download.

piyushk gravatar image piyushk  ( 2012-09-05 11:51:27 -0500 )edit

@Lorenz: See updated answer for downloadable code example

piyushk gravatar image piyushk  ( 2012-09-05 12:17:35 -0500 )edit

I don't have a good explanation as to why this happens, but I had to use tf::messagefilters instead of waitfortransform to resolve a similar issue

phil0stine gravatar image phil0stine  ( 2012-09-05 13:34:04 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
3

answered 2012-09-05 18:49:45 -0500

I have tracked this problem down to this to Line 602 in tf.cpp in the waitForTransform function.

I believe if ros::Time::now() is called immediately after creating the transformListener, it incorrectly returns a value of 0. I am not sure in what situations this occurs, but it does so in the bag provided in the question. Once the polling in waitForTransform starts and ros::Time::now() finally kicks in to the current ROS time, if the timeout is less than the current ROS Time (highly likely) then the wait call gets thrown out. If the timeout is higher, then the next round of polling returns the frame and the call succeeds.

A simple (hack) solution to this problem is placing a sleep between creating the transformListener object and calling waitForTransform. sleep(5) in the demo code provided makes it work correctly independent of timeout duration.

This bug has been reported. https://code.ros.org/trac/ros-pkg/ticket/5551

edit flag offensive delete link more

Comments

I guess the problem is actually that, if sim time is enable and clock is not published yet, the current time ros::Time::now() is always zero. That is, as far as I know, by intention. I remember that you are not the first one who ran into this and I think it was ticketed before.

Lorenz gravatar image Lorenz  ( 2012-09-05 21:56:24 -0500 )edit

@Lorenz: /clock was being published. Perhaps the node did not have enough time to receive a /clock message before calling ros::Time::now()? That seems a bit odd.

piyushk gravatar image piyushk  ( 2012-09-06 05:20:29 -0500 )edit

Actually, to me it doesn't seem odd at all :) It takes a while until the tcpip connection between a publisher and a subscriber is set up because there are a few xmlrpc requests and topic negotiation involved.

Lorenz gravatar image Lorenz  ( 2012-09-06 05:22:45 -0500 )edit

@Lorenz: Sorry, I meant this from an overall design issue. I realize that it will take some time to receive a /clock message. If /use_sim_time is set it might almost make sense for every node to try and wait for the /clock message for some duration of wall time.

piyushk gravatar image piyushk  ( 2012-09-06 05:26:49 -0500 )edit

Yes. i think so, too. Unfortunately nobody answered yet on your ticket or the ticket that was opened before on the issue. But I guess throwing an error or blocking instead of returning 0 for ros::Time::now would definitely be a better solution :)

Lorenz gravatar image Lorenz  ( 2012-09-06 05:30:20 -0500 )edit

Question Tools

Stats

Asked: 2012-09-05 09:05:35 -0500

Seen: 3,348 times

Last updated: Sep 05 '12