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

TF2 ConnectivityException With Connected TF Tree

asked 2020-02-18 15:54:45 -0500

rwbot gravatar image

I'm getting the following error about missing frames, but when I view the TF tree, it shows as a single connected tree. The same error occurs no matter which two frames I use. I don't have enough karma to post a screenshot or PDF of the TF Tree.

[ERROR]: bad callback: <function dockPoseCallback at 0x7f55bacf44d0>
Traceback (most recent call last):
  File "/opt/ros/melodic/lib/python2.7/dist-packages/rospy/topics.py", line 750, in _invoke_callback
    cb(msg)
  File "/home/rwbot/dock_ws/src/docking/src/controller.py", line 31, in dockPoseCallback
    dockTF = tfBuffer.lookup_transform('world', 'base_link', rospy.Time())
  File "/opt/ros/melodic/lib/python2.7/dist-packages/tf2_ros/buffer.py", line 87, in lookup_transform
    return self.lookup_transform_core(target_frame, source_frame, time)
ConnectivityException: Could not find a connection between 'world' and 'base_link' because they are not part of the same tree.Tf has two or more unconnected trees.

When I run rosrun tf2_tools echo.py world base_link it gives the transform which at least verifies that the frames do in fact exist.

rwbot@carowe:~/dock_ws$ rosrun tf2_tools echo.py world base_link
At time 1654.916, (current time 1654.921)
- Translation: [-0.001, -0.002, 0.077]
- Rotation: in Quaternion [-0.000, -0.003, -0.004, 1.000]
            in RPY (radian) [-0.000, -0.005, -0.008]
            in RPY (degree) [-0.002, -0.291, -0.430]

Here is the relevant code

#!/usr/bin/env python
import math
from visualization_msgs.msg import *
import rospy
import tf2_ros
import tf2_geometry_msgs
from geometry_msgs.msg import *
from nav_msgs.msg import *
from std_msgs.msg import *
from docking.msg import *

def dockPoseCallback(dockPose):
    LOS = docking.msg.LineOfSight()
    tfBuffer = tf2_ros.Buffer()
    listener = tf2_ros.TransformListener(tfBuffer)
    dockTF = tfBuffer.lookup_transform('world', 'base_link', rospy.Time())

def main():
    rospy.init_node("controller")
    dock_pose_sub = rospy.Subscriber('dock_pose', PoseStamped, dockPoseCallback)
    LOS_marker_pub = rospy.Publisher('LOS', Marker, queue_size=10)
    r = rospy.Rate(10)  # 10hz

    while not rospy.is_shutdown():
        LOS_marker_pub.publish(LOS.arrow)
        r.sleep()

if __name__ == '__main__':
    main()
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
3

answered 2020-02-18 16:17:31 -0500

tfoote gravatar image

You're creating the buffer and listener inside your callback which does not give them any time to populate the buffer to run queries against. If you query the buffer immediately after creating it it will have not aggregated any data yet. You need to make sure to have the buffer and listener created and persistent outside your callback.

Please see the tutorial for an example: https://wiki.ros.org/tf2/Tutorials/Wr...

A similar question is here: https://answers.ros.org/question/2837...

There's some good details here: https://answers.ros.org/question/3267...

edit flag offensive delete link more

Comments

exactly what i needed!

rwbot gravatar image rwbot  ( 2020-03-02 12:38:33 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2020-02-18 15:54:45 -0500

Seen: 560 times

Last updated: Feb 18 '20