Problem listening to static transform

Hi all!
I’m trying to get the static transform between two frames: frame1 and frame2.
For that I am playing with two different codes, one works but the other not and throw me the following exception:

“[INFO] [1678049163.397226346] [transform_frame_node]: Could not transform frame2 to frame1: “frame1” passed to lookupTransform argument target_frame does not exist.”

the two codes are rather similar. The difference is that in one I call lookup_transform() inside a timer function callback and in the other I call it inside a loop.

Can someone help me and tell me why the second code doesn’t work?

WORKING CODE:

    import sys
    import rclpy
    from rclpy.node import Node
    
    from tf2_ros import LookupException, ConnectivityException, ExtrapolationException
    from tf2_ros.buffer import Buffer
    from tf2_ros.transform_listener import TransformListener
    
    class FrameListener(Node):
    
        def __init__(self):
            super().__init__('frame_listener_node')
    
            self.from_frame = sys.argv[1]
            self.to_frame = sys.argv[2]
    
            self.tf_buffer = Buffer()
            self.tf_listener = TransformListener(self.tf_buffer, self)
    
            # Call on_timer function every second
            self.timer = self.create_timer(1.0, self.on_timer)
    
    
        def on_timer(self):
    
            try:
                now = rclpy.time.Time()
                tf = self.tf_buffer.lookup_transform(
                    self.to_frame,
                    self.from_frame,
                    now)
    
                self.get_logger().info("TF from '"  + self.from_frame + "' to '" + self.to_frame + "'-> " + str(tf.transform.translation))
                self.get_logger().info("TF from '"  + self.from_frame + "' to '" + self.to_frame + "'-> " + str(tf.transform.rotation))
    
            except (LookupException, ConnectivityException, ExtrapolationException)as ex:
                self.get_logger().info(
                    f'Could not transform {self.from_frame} to {self.to_frame}: {ex}')
                return
    
    
    def main():
    
        rclpy.init()
        assert len(sys.argv) != 2, "Please add all the arguments: from_frame to_frame"
        node = FrameListener()
        try:
            rclpy.spin(node)
        except KeyboardInterrupt:
            pass
    
        rclpy.shutdown()

NON WORKING CODE:

    import sys
    import rclpy
    from rclpy.node import Node
    
    from tf2_ros import LookupException, ConnectivityException, ExtrapolationException
    from tf2_ros.buffer import Buffer
    from tf2_ros.transform_listener import TransformListener
    
    
    class FrameListener(Node):
    
        def __init__(self):
            super().__init__('transform_frame_node')
    
            self.from_frame = sys.argv[1]
            self.to_frame = sys.argv[2]
    
            self.tf_buffer = Buffer()
            tf_listener = TransformListener(self.tf_buffer, self)
    
            tf = self.get_transform(self.from_frame, self.to_frame)
            print(tf)
    
    
        def get_transform(self, from_frame, to_frame):
    
            tf = None
            while (tf == None):
                try:
                    now = rclpy.time.Time()
                    tf = self.tf_buffer.lookup_transform(to_frame, from_frame, now, timeout=rclpy.duration.Duration(seconds=5.0))
    
                    self.get_logger().info("TF from '"  + from_frame + "' to '" + to_frame + "'-> " + str(tf.transform.translation))
                    self.get_logger().info("TF from '"  + from_frame + "' to '" + to_frame + "'-> " + str(tf.transform.rotation))
                    
                except (LookupException, ConnectivityException, ExtrapolationException)as ex:
                    self.get_logger().info(
                        f'Could not transform {from_frame} to {to_frame}: {ex}')
                    return
    
    def main():
    
        rclpy.init()
        assert len(sys.argv) !=2, "Please add all the arguments: from_frame to_frame"
        node = FrameListener()
        try:
            rclpy.spin(node)
        except KeyboardInterrupt:
            pass
    
        rclpy.shutdown()

Regards.

Hello @joseecm,

I noticed that your code is entering a while loop during object initialization. Per se is it not wrong to enter a loop during object initialization as long as the loop does not cause any unwanted side effects or take an excessive amount of time to execute.
However, in this case you are relying on external resources, the TF must exist for the loop to exit. Also when you enter the while loop, everything else is blocked. Because of this your code can’t execute the rclpy.spin(node) part that updates the callbacks and gets new TF information from the ROS network. This does not happen when you implement a timer, since the timer is non-blocking.

Hope this helps,

Roberto

Thanks for your answer Roberto.
You are right. I didn’t realize that if the code can’t execute rclpy.spin(node)
then it can’t get new TF information.
I have check that a solution for that is to run TransformListener in his own thread using the spin_thread parameter:

TransformListener(self.tf_buffer, self, spin_thread = True)

Using this parameter the code can update the TF information even if it has not yet executed rclpy.spin(node).

Regards,

Jose Enrique.

1 Like

This topic was automatically closed 5 days after the last reply. New replies are no longer allowed.