frame passed to lookupTransform does not exist
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