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

frame passed to lookupTransform does not exist

asked 2015-02-17 07:24:52 -0600

Yorick gravatar image

I have encountered a peculiar error with the tf. The python lookupTransform function throws an exception saying that requested frame does not exists whereas tools like tf_echo do not report any problems. Since the setup I am trying to run is extremely simple, I have no idea what could be wrong. Either I have missed something very simple which I can't see right now or this is a bug in tf.

I am running stage with the willow-erratic.world file: rosrun stage_ros stageros -g willow-erratic.world together with the following node:

#!/usr/bin/env python
import rospy
import tf
from sensor_msgs.msg import LaserScan

listener = tf.TransformListener()

def scanCb(msg):
        print 'laserscan received'
        print msg.angle_max   

        # lookup base_link -> laser frame transformation
        (trans, rot) = listener.lookupTransform('base_link', 'base_laser_link', rospy.Time())

rospy.init_node('console_interface')
rospy.Subscriber('/base_scan', LaserScan, scanCb)
rospy.spin()

The output is:

laserscan received
2.35837626457
[ERROR] [WallTime: 1424179111.916555] [4010.900000] bad callback: <function scanCb at 0x7fa22abe2cf8>
Traceback (most recent call last):
  File "/opt/ros/indigo/lib/python2.7/dist-packages/rospy/topics.py", line 688, in _invoke_callback
    cb(msg)
  File "/home/vagrant/test_ws/src/scout_nav/scripts/console_iface", line 14, in scanCb
    (trans, rot) = listener.lookupTransform('base_link', 'base_laser_link', rospy.Time())
LookupException: "base_link" passed to lookupTransform argument target_frame does not exist.

tf_echo does not seem to have problems with looking up the transform:

rosrun tf tf_echo base_link base_laser_link
At time 4147.200
- Translation: [0.050, 0.000, 0.250]
- Rotation: in Quaternion [0.000, 0.000, 0.000, 1.000]
            in RPY [0.000, -0.000, 0.000]

Does anyone see what is wrong with my approach?

Thanks

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
5

answered 2015-02-17 08:03:08 -0600

Yorick gravatar image

I figured out what was causing the problem...

The call listener = tf.TransformListener() should be after the node initialization.

edit flag offensive delete link more

Comments

Yeah that is definitely a problem as well! I missed that :) ... I do believe my answer still provides several useful tips.

jarvisschultz gravatar image jarvisschultz  ( 2015-02-17 08:11:52 -0600 )edit
2

I'm quite sure that even if you swap the order of the listener creation and the call to init_node, your node will occasionally crash with the same error you originally presented if, just by chance, the /base_scan topic gets published immediately after the creation of the Subscriber.

jarvisschultz gravatar image jarvisschultz  ( 2015-02-17 08:16:20 -0600 )edit

For what it's worth, I was having this error about target_frame not existing and played with incantations of where to define listener, but my issue ended up being this one. Namely, use tf2.

jwhendy gravatar image jwhendy  ( 2017-07-05 10:13:22 -0600 )edit

Also worth noting, it seems that sometimes if you call lookupTransform too quickly after init_node you will get the error shown in the original question. To deal with this, you can use waitForTransform first, e.g.:

listener = tf.TransformListener()
listener.waitForTransform("/frame1", "/frame2", rospy.Time(), rospy.Duration(4.0))
(trans, rot) = listener.lookupTransform("/frame1", "/frame2", rospy.Time(0))
M@t gravatar image M@t  ( 2019-06-30 00:38:01 -0600 )edit

I had a similar issue and adding rospy.Duration(4) was essential

ignacio gravatar image ignacio  ( 2021-03-08 03:46:40 -0600 )edit
10

answered 2015-02-17 08:08:11 -0600

updated 2015-02-18 08:59:05 -0600

As a first debugging step, I'd recommend wrapping your call to lookupTransform in a try-except block. Just like they do in lines 23-26 of the Python tf listener tutorial. After the creation of the listener, it usually takes a few seconds to negotiate all of the connections, and to get the listener to start filling its buffers. I'm guessing that you are seeing your error because you are asking for a transform too soon after the creation of the listener.

Another thing you could do is wait for the transform to become available before requesting a lookup.

As a final note, be aware that even if all of your tf code is functioning properly, due to the asynchronous nature of ROS, your call to lookupTransform is likely to fail occasionally. This is usually because of timing issues. I always wrap calls to lookupTransform in a try and except block of some sort.

edit flag offensive delete link more

Comments

Good explanation, and thanks!

arkin gravatar image arkin  ( 2020-04-27 21:15:15 -0600 )edit

Question Tools

Stats

Asked: 2015-02-17 07:24:52 -0600

Seen: 20,679 times

Last updated: Feb 18 '15