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

tf_echo can find transform but waitForTransform can't

asked 2016-04-14 08:11:06 -0600

Mehdi. gravatar image

updated 2016-04-14 09:19:58 -0600

For some reason, listening to the transforms between robot_center and laser_link from the network does not work anymore. In my Python script, I do:

self.tf_listener.waitForTransform("robot_center",
                                          "/base_front_laser_link",
                                          rospy.Time(0),
                                          rospy.Duration(5))

and get a timeout after 5 seconds. From the same terminal, when I run

rosrun tf tf_echo robot_center /base_front_laser_link

It works and I can see the transform. Both my laptop and the robot's computer's time are synchronized using NTP. Whan can be the reason for this behaviour?

EDIT:

I also tried running my script directly on the robot, still no difference, always timeout.

EDIT2:

I found out that a change was made recently in my robot where the static transforms are published with a time = 0.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
4

answered 2016-04-18 03:52:06 -0600

Mehdi. gravatar image

updated 2016-04-18 07:52:53 -0600

The problem was that our robot's state publisher was changed such that most of static transforms representing rigid links were published using tf2 for efficiency reasons. Publishing them as static transforms, their timestamps are always set to zero. It was normal that waiting for transform did not work. Using tf2 however solved the problem.

    self.tf_buffer = tf2_ros.Buffer()
    self.tf2_listener = tf2_ros.TransformListener(self.tf_buffer)
    transform = self.tf_buffer.lookup_transform("robot_center",
                                                "base_front_laser_link_horizontal",
                                                rospy.Time(0),
                                                rospy.Duration(10))
edit flag offensive delete link more

Comments

Aaaaahahhhhhhh. As a ROS noob, I banged my head against the wall for ~2.5 days on this exact issue. I'm following along with ROS Industrial tutorials, but doing them in python. This was exactly what went wrong (yet I suspected myself because I'm a noob and that was 10x more likely). Thanks!

jwhendy gravatar image jwhendy  ( 2017-07-04 21:01:31 -0600 )edit

Hi! I'm sorry, I didn't quite understand. You said tf2 was used for efficiency reasons, and that static transforms in tf2 have their timestamps set to zero, but then you mention that you've used tf2 again to solve the problem. How did you solve it with tf2? @jwhendy

felipeduque gravatar image felipeduque  ( 2019-11-29 08:26:23 -0600 )edit
1

@felipeduque just as above. They key is that instead of using the code here, use the code here. Because the static transforms were published with tf2, you have to look them up using tf2 vs. tf. Does that make sense?

jwhendy gravatar image jwhendy  ( 2020-01-08 15:17:32 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2016-04-14 08:11:06 -0600

Seen: 2,273 times

Last updated: Apr 18 '16