rclpy BufferClient strange timeout on lookup_transform
System Info:
- Operating System:
- Docker + Ubuntu 20.04
- Installation type:
- From binaries
- Version or commit hash:
- Foxy
- DDS implementation:
- Fast-RTPS
Steps to reproduce issue
Calling BufferClient.lookup_transform
always timeouts although if I call the buffer server via ros2 cli it works.
TestNode
Create a node like the following:
#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from tf2_ros.buffer_client import BufferClient
from rclpy.duration import Duration
from std_msgs.msg import Empty
class TestNode(Node):
def __init__(
self,
):
super().__init__("test_node")
self.cb_group = None
self.buffer = BufferClient(
self,
"/tf2_buffer_server",
timeout_padding=1.0,
callback_group=self.cb_group,
)
self.sub = self.create_subscription(
msg_type=Empty,
topic="/test_buffer_client",
callback=self.buffer_cb,
qos_profile=1,
)
def buffer_cb(self, msg):
_ = self.buffer.lookup_transform(
"map",
"odom",
rclpy.time.Time(seconds=0, nanoseconds=0),
timeout=Duration(seconds=1.0),
)
self.get_logger().info("Success")
def main(args=None):
rclpy.init(args=args)
node = TestNode()
executor = None
rclpy.spin(node, executor)
if __name__ == "__main__":
main()
Make sure the buffer server is already running (ros2 run tf2_ros buffer_server
) and there is a valid transform between map->odom (it could be as simple as an identity transform -> ros2 run tf2_ros static_transform_publisher 0 0 0 0 0 0 map odom
).
Then publish to the topic that calls BufferClient.lookup_transform
.
ros2 topic pub -1 /test_buffer_client std_msgs/msg/Empty
The traceback is:
Traceback (most recent call last):
File "/workspace/rover/ros2/install/navigation/lib/navigation/navigation_test", line 33, in <module>
sys.exit(load_entry_point('navigation', 'console_scripts', 'navigation_test')())
File "/workspace/rover/ros2/build/navigation/navigation/node_test.py", line 53, in main
rclpy.spin(node, executor)
File "/opt/ros/foxy/lib/python3.8/site-packages/rclpy/__init__.py", line 191, in spin
executor.spin_once()
File "/opt/ros/foxy/lib/python3.8/site-packages/rclpy/executors.py", line 711, in spin_once
raise handler.exception()
File "/opt/ros/foxy/lib/python3.8/site-packages/rclpy/task.py", line 239, in __call__
self._handler.send(None)
File "/opt/ros/foxy/lib/python3.8/site-packages/rclpy/executors.py", line 426, in handler
await call_coroutine(entity, arg)
File "/opt/ros/foxy/lib/python3.8/site-packages/rclpy/executors.py", line 351, in _execute_subscription
await await_or_execute(sub.callback, msg)
File "/opt/ros/foxy/lib/python3.8/site-packages/rclpy/executors.py", line 118, in await_or_execute
return callback(*args)
File "/workspace/rover/ros2/build/navigation/navigation/node_test.py", line 33, in buffer_cb
_ = self.buffer.lookup_transform(
File "/opt/ros/foxy/lib/python3.8/site-packages/tf2_ros/buffer_client.py", line 87, in lookup_transform
return self.__process_goal(goal)
File "/opt/ros/foxy/lib/python3.8/site-packages/tf2_ros/buffer_client.py", line 201, in __process_goal
raise tf2.TimeoutException("The LookupTransform goal sent to the BufferServer did not come back in the specified time. Something is likely wrong with the server")
tf2.TimeoutException: The LookupTransform goal sent to the BufferServer did not come back in the specified time. Something is likely wrong with the server
Expected behavior
It shouldn't crash since it works with the ros2 cli. If you use the following it works:
ros2 action send_goal /tf2_buffer_server tf2_msgs/action/LookupTransform '{target_frame: map, source_frame ...