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

Using tf to transform a point

asked 2012-06-06 23:58:48 -0600

Hansg91 gravatar image

Hello,

I am trying to transform a point from one frame (/kinect_frame) to another (/base_link).

This is the pdf I get from 'rosrun tf view_frames' :

image description

but still when I try to transform my point using a tf::TransformListener and tf::TransformListener::transformPoint like this :

mTransformListener.transformPoint("/base_link", qc.response.points[0], result);

I get the following error :

[ERROR] [1339062545.681343977]: Unable to lookup transform, cache is empty, when looking up transform from frame [/kinect_frame] to frame [/base_link]

But there is a link visible between kinect_frame and base_link, what am I doing wrong ?

edit retag flag offensive close merge delete

3 Answers

Sort by ยป oldest newest most voted
8

answered 2012-06-07 09:20:14 -0600

Lorenz gravatar image

You need to make sure that TF has a valid and complete TF tree to transform from the kinect frame at the time stamp of the point you are transforming. That's the case when TF received a transform with a stamp greater or equal than the time stamp of the point you are trying to transform. The reason is that TF tries to interpolate positions and orientations, but does not extrapolate. Of course, for interpolation, TF needs at least two transforms, one after and one before the time stamp you are trying to transform.

The static_transform_publisher future-dates transforms to make sure that all data that uses ros::Time::now() can actually be transformed and to avoid unnecessary delays but it cannot be assumed that frames published by other nodes are future dated as well. For instance, when you have a moving frame (e.g. a PTU), you can only use the current position of the frame (i.e. ros::Time::now()) to publish a frame, everything in the future would be extrapolation again. For that reason, TF provides the method waitForTransform that allows to block until a timeout expires or the transformation into a frame becomes possible. Alternatively, tf::MessageFilter can be used to postpone a subscriber callback on a stamped message until the transformation into a specific frame is possible.

edit flag offensive delete link more

Comments

Thanks :) One last question, when I have the StampedTransform from lookupTransform, how do I use that to transform a point from frame A to frame B ? I couldn't find it in the tutorials and I don't think it is a big enough question to start a new post :)

Hansg91 gravatar image Hansg91  ( 2012-06-08 02:14:37 -0600 )edit

Use transformPoint instead of lookupTransform. It's a member function of tf::TransformListener (quick link: http://ros.org/doc/fuerte/api/tf/html/c++/classtf_1_1TransformListener.html).

Lorenz gravatar image Lorenz  ( 2012-06-08 02:16:56 -0600 )edit

Silly me, I thought I had to use lookupTransform after waitForTransform, but transformPoint will do :D thnx again

Hansg91 gravatar image Hansg91  ( 2012-06-08 03:23:37 -0600 )edit
1

answered 2012-06-07 04:36:54 -0600

Hansg91 gravatar image

I was trying out some few things and I found out the problem is resolved if I replace my dynamic tf publisher with a static one, like this :

<node pkg="tf" type="static_transform_publisher" name="head_to_kinect_normal_axis" args="-0.03 0.055 0.12 0 0 -0.4 head_frame kinect_normal_axis_frame 20" />

But I really need it to be dynamic ... so this is where my answer ends and a new question arises. The dynamic publishing is done through a tf::TransformBroadcaster. I don't initialize it and I use it like this :

mKinectTFBroadcaster.sendTransform(tf::StampedTransform(mKinectTF, ros::Time::now(), "head_frame", "kinect_normal_axis_frame"));

And as can be seen in the picture of my original question, this does indeed get published. I have no idea what seems to be the problem.

edit flag offensive delete link more

Comments

According to the picture above, you publish with 10Hz. Did you try adding calls to waitForTransform before calling transformPoint?

Lorenz gravatar image Lorenz  ( 2012-06-07 04:44:57 -0600 )edit

The static tranform publishers publish at 10Hz, the node publishes at 50Hz, but after I change the static one to 50Hz it still works. So I don't believe it is the frequency. And as you can see by the picture, if I sent it only once, then the frequency would not be 10-50Hz.

Hansg91 gravatar image Hansg91  ( 2012-06-07 05:25:24 -0600 )edit

Is there perhaps something wrong with how I send the time? Thats the only thing I can think of ...

Hansg91 gravatar image Hansg91  ( 2012-06-07 05:26:04 -0600 )edit

Deleted my misleading comment. Of course you are publishing at 50Hz, not 500. Sorry. Did you try adding waitForTransform to your code? Using ros::Time::now() as time stamp should be fine.

Lorenz gravatar image Lorenz  ( 2012-06-07 05:30:33 -0600 )edit

I think I know what it is: the static_transform_publisher future-dates the transforms it sends, your code doesn't. Instead of using ros::Time::now(), you can do something like ros::Time::now() + ros::Duration(0.1). I think using a tf::MessageFilter or waitForTransform is good practice though.

Lorenz gravatar image Lorenz  ( 2012-06-07 05:42:32 -0600 )edit

Wow, that was it, so weird ... why does the static transform publisher do that? Could you post it as an answer so I can up it :)

Hansg91 gravatar image Hansg91  ( 2012-06-07 09:00:40 -0600 )edit
1

answered 2012-06-07 00:08:33 -0600

Lorenz gravatar image

updated 2012-06-07 00:21:18 -0600

Just a guess: are you maybe instantiating a new tf::TransformListener right before you are calling transformPoint, i.e. in the same function you are calling transformPoint? This won't work because it takes some time until new tf messages are received and the TransformListener's cache is filled. Instead, you should instantiate the TransformListener at the beginning of your program.

The same can happen if you call transformPoint too early in your program, i.e. when there were no messages on /tf received so far. To avoid that, or if you are getting extrapolation errors, have a look at waitForTransform and this tutorial or tf::MessageFilter.

edit flag offensive delete link more

Comments

Thank you for your response. Actually, I'm creating an object which has the tf::TransformListener as a member. I don't initialise it or anything, I thought that was not needed (?).

Hansg91 gravatar image Hansg91  ( 2012-06-07 00:17:31 -0600 )edit

Actually, you can check the code here : http://code.google.com/p/roman-technologies/source/browse/trunk/image_processing/src/PersonTracker.cpp The transformPoint is done in getWorldPoint

Hansg91 gravatar image Hansg91  ( 2012-06-07 00:18:21 -0600 )edit

You are right. No initialization needed. It was just a guess because I've seen people instantiating new TransformListener objects whenever they need to transform anything.

Lorenz gravatar image Lorenz  ( 2012-06-07 00:19:27 -0600 )edit

Question Tools

Stats

Asked: 2012-06-06 23:58:48 -0600

Seen: 16,107 times

Last updated: Jun 07 '12