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

Target_frame does not exist but its found by tf2_tools echo.

asked 2022-04-25 06:58:27 -0500

mth_sousa gravatar image

Hello everyone! I'm facing an strange issue with the code below. It's suposed to get the distance between two apriltag tags but it reports that the target frame doesn't exist.

I searched in http://wiki.ros.org/tf2/Tutorials/Deb... but everything looks correct for me. Even if I wait a lot the transformation between the two tags never becomes available.

import tf2_ros
import tf_conversions
import geometry_msgs
import rospy
from math import pi
import time

rospy.init_node('treeLink')
print("Nó iniciado")
tfBuffer = tf2_ros.Buffer(rospy.Duration(secs=2))
listener = tf2_ros.TransformListener(tfBuffer)
print("Listener iniciado")
br = tf2_ros.TransformBroadcaster()
print("Broadcaster iniciado")

    rate = rospy.Rate(10.0)

    syncTime = 0

    last_published_timestamp = rospy.Time(0)

    tree_link = geometry_msgs.msg.TransformStamped()

    tags = ["tag_0","tag_1","tag_2","tag_3","tag_4"] 

    while not rospy.is_shutdown():
                for n in range(0,len(tags)):
                    (trans,rot) = tfBuffer.lookup_transform("tag_2",tags[n],rospy.Time())
                    print("----------------------------------------------------")
                    print("Posição atual da" + tags[n] +":")
                    print("Translação")
                    print(trans)
                    print("Rotação")
                    print(rot)
            # except:
                if time.time() - syncTime > 1:
                    syncTime = time.time()
                    print("...")

matheus@matheus:~/catkin_ws/src/main/scripts/testes$ python3 showTagPos.py

Traceback (most recent call last):

File "showTagPos.py", line 86, in <module> (trans,rot) = tfBuffer.lookup_transform("tag_2",tags[n],rospy.Time())

File "/opt/ros/noetic/lib/python3/dist-packages/tf2_ros/buffer.py", line 86, in lookup_transform return self.lookup_transform_core(target_frame, source_frame, time)

tf2.LookupException: "tag_2" passed to lookupTransform argument target_frame does not exist.

matheus@matheus:~/catkin_ws/src/main/scripts/testes$ rosrun tf2_tools echo.py tag_2 tag_0

At time 3560.65, (current time 3560.72)

  • Translation: [0.543, 0.218, -0.027]
  • Rotation: in Quaternion [0.066, -0.187, 0.041, 0.979] in RPY (radian) [0.122, -0.380, 0.061] in RPY (degree) [6.985, -21.761, 3.481] At time 3560.65, (current time 3560.72)
  • Translation: [0.543, 0.218, -0.027]
  • Rotation: in Quaternion [0.066, -0.187, 0.041, 0.979] in RPY (radian) [0.122, -0.380, 0.061]

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
0

answered 2022-04-25 16:37:22 -0500

tfoote gravatar image

It's likely that you're starving your listener of time to subscribe and receive incoming messages as you're continuously calling lookup_transform and never letting the node process incoming messages. If they are coming in enough you definitely won't get them all in the first pass while the buffer is filling and you need to make it robust to retrying the queries after the connections have been established to the different sources of the tf streams.

Take a look at the tutorials where there's a try/except block and a sleep.

http://wiki.ros.org/tf2/Tutorials/Wri...

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2022-04-25 06:58:27 -0500

Seen: 305 times

Last updated: Apr 25 '22