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

tf::TransformListener::transformPose [exception] target_frame does not exist

asked 2014-09-12 08:15:52 -0500

bvbdort gravatar image

updated 2014-09-13 01:07:50 -0500

Hi,

I am trying to transform geometry_msgs::PoseStamped in one frame to other. I am using tf::TransformListener::transformPose here is my code snippet.

 tf::TransformListener listener;
  geometry_msgs::PoseStamped pose_map;
  try{
  listener.transformPose("map",pose_world,pose_map); // pose_world is in world frame
  }
  catch( tf::TransformException ex)
  {
      ROS_ERROR("transfrom exception : %s",ex.what());
  }

i am getting below exception.

[ERROR] [1410527449.677789054, 1410185755.142016150]: transfrom exception : "map" passed to lookupTransform argument target_frame does not exist.

But i can see tf between /world and /map from rosrun tf view_frames and also from rosrun tf tf_echo world map

Edit:

After adding wait for transform i am getting below exception. But /map to /world is publishing at 25hz from launch file. I am using bag file for tf data with --clock and use_sim_time true

[ERROR] [1410539110.856303453, 1410185780.612246601]: transfrompose exception : Lookup would require extrapolation into the past. Requested time 1410185779.600078575 but the earliest data is at time 1410185779.862480216, when looking up transform from frame [world] to frame [map]

Thank you.

edit retag flag offensive close merge delete

Comments

You're running roscore first, then setting use_sim_time, then starting your launch file, then running rosbag play, correct?

Tom Moore gravatar image Tom Moore  ( 2014-09-13 08:27:59 -0500 )edit

i put use_sim_time param in launch file as first line. First launch file then rosbag play

bvbdort gravatar image bvbdort  ( 2014-09-13 08:53:33 -0500 )edit

Can you post the relevant parts of your launch file?

Tom Moore gravatar image Tom Moore  ( 2014-09-13 09:01:28 -0500 )edit
bvbdort gravatar image bvbdort  ( 2014-09-13 10:25:07 -0500 )edit

And you're certain that the original data (before you bagged it) didn't also have this problem? Try playing back the bag file very slowly (with -r) and watch the message time stamps. If the tf ones seem out of sync, then perhaps your original data (i.e., on the live robot) had this problem as well.

Tom Moore gravatar image Tom Moore  ( 2014-09-13 15:59:01 -0500 )edit

I didnt try with live data so far, but in rosbag data I can see all the required tf from rostopic echo.

bvbdort gravatar image bvbdort  ( 2014-09-13 16:46:30 -0500 )edit

But the bag data came from somewhere. The question isn't whether the tranforms exist. It's whether they have the correct time stamps. If there was something wrong when you recorded the data, it won't get better when you replay it.

Tom Moore gravatar image Tom Moore  ( 2014-09-13 18:38:28 -0500 )edit

Does this error happen once or a few times at startup or does it continuously happen?

tfoote gravatar image tfoote  ( 2014-09-13 23:31:35 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
16

answered 2014-09-15 08:47:51 -0500

Tom Moore gravatar image

updated 2014-09-15 08:51:26 -0500

Quick question: is the code you posted in your question inside a callback? If so, you need to not create the TransformListener object inside of it. Try making it a member variable if it's a class or a global variable otherwise and see if that helps.

If it doesn't, then there might be one or two other issues (at least that I noticed). Here's what I did:

  1. Stripped your launch file down to just the static_transform_publisher
  2. Opened up a console and started a roscore
  3. Opened up another console and launched your file
  4. Opened up two more consoles and echoed your /pose and /odom topics.
  5. Opened up a final console and echoed the tf topic.
  6. Did rosbag play bagfile.bag --clock -r 0.01.
  7. I then waited for the pose message to get updated, paused the playback, and looked at your available transforms from the tf topic.

Here's what I found:

  1. The time stamps between your pose, odom, and tf world->map transforms were all sufficiently small.
  2. Your /pose topic has no frame_id. Not sure how you're getting your pose_world object above, but you might want to check that.

So, without running your whole system, my best guess is that something is blocking the processing of your incoming data, i.e., you get a pose message, but then a large amount of time passes before you attempt to transform it, at which point the transforms are too old. Try doing what I suggested above with your TransformListener (assuming this is in a callback) and also adding a frame_id to your /pose topic.

edit flag offensive delete link more

Comments

@thanks for answer, it was working but still showing exception sometimes(but very less ) i moved transformlistner to class variable from local variable inside timesynchronizer. Yes i am using this code inside timesynchronizer callback. /pose topic i am copying to pose_world and adding frame id.

bvbdort gravatar image bvbdort  ( 2014-09-15 15:42:11 -0500 )edit

timesynchronizer is waiting for laser and pose messages which have same timestamps.

bvbdort gravatar image bvbdort  ( 2014-09-15 15:43:02 -0500 )edit
2

Ah, good. Yeah, there's some overhead when you first declare a TransformListener, and so you should re-use the same one.

Tom Moore gravatar image Tom Moore  ( 2014-09-15 18:53:18 -0500 )edit

Thank you, Tom. It still applies for nowadays TF2 tfBuffer.lookupTransform. Just making it a member variable if it's a class or a global variable otherwise out of the callback solve my issue.

HaFred gravatar image HaFred  ( 2021-12-09 02:51:20 -0500 )edit
4

answered 2014-09-12 09:42:34 -0500

Chrissi gravatar image

updated 2018-08-04 20:37:23 -0500

130s gravatar image

It might be that there is no transformation published for these timestamps at the time you want to transform them. Have a look at this tutorial) especiall at '3. Wait for transforms'.

Edit: I'm not sure if this important but try /map instead of map

edit flag offensive delete link more

Comments

thanks for reply, tf is available when i use rosrun tf tf_echo world map at sametime . Also tried with /map too but same result. Actually it was static transform which i am sending from launch file and i wantt to convert pose between them.

bvbdort gravatar image bvbdort  ( 2014-09-12 09:53:57 -0500 )edit

Please just try the wait for transform thing in the tutorial. That should fix it.

Chrissi gravatar image Chrissi  ( 2014-09-12 10:18:59 -0500 )edit

--[ERROR] [1410539110.856303453, 1410185780.612246601]: transfrompose exception : Lookup would require extrapolation into the past. Requested time 1410185779.600078575 but the earliest data is at time 1410185779.862480216, when looking up transform from frame [world] to frame [map]--

bvbdort gravatar image bvbdort  ( 2014-09-12 11:28:45 -0500 )edit

above is the exception after adding wait for transform. But /map to /world is publishing at 25hz from launch. I have to say i am using bag file for data with --clock and use_sim_time true

bvbdort gravatar image bvbdort  ( 2014-09-12 11:33:11 -0500 )edit

Thanks for the suggestion! I was able to solve this problem with:

got_transform = False
while not got_transform:
    try:
        (callbacks.trans_mat, callbacks.rot_mat) = callbacks.tf_listener.lookupTransform('map', 'odom', rospy.Time(0))
        got_transform = True
    except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException):
        continue
user1928 gravatar image user1928  ( 2022-08-24 13:17:14 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2014-09-12 08:15:52 -0500

Seen: 27,619 times

Last updated: Aug 04 '18