Open charlielito opened 3 years ago
I am also having the same issue in rclpp
, when using this inside a callback the BufferClient.lookupTransform
timeouts.
@clalancette I see there are some tests for this but not for testing it inside a callback function.
I have the same problem - I think this feature is actually not ready to be used?
I am also having the same issue in
rclpp
, when using this inside a callback theBufferClient.lookupTransform
timeouts. @clalancette I see there are some tests for this but not for testing it inside a callback function.
For better or worse, that is by design. The problem with doing this is that you are blocking the executor, but the executor needs to run in order to get the transform.
The solution here is to make sure to never run blocking functions like lookupTransform
from within a callback, or you use the MultiThreadedExecutor, or you instantiate the TransformListener
with spin_thread = True
.
I am also having the same issue in
rclpp
, when using this inside a callback theBufferClient.lookupTransform
timeouts. @clalancette I see there are some tests for this but not for testing it inside a callback function.For better or worse, that is by design. The problem with doing this is that you are blocking the executor, but the executor needs to run in order to get the transform.
The solution here is to make sure to never run blocking functions like
lookupTransform
from within a callback, or you use the MultiThreadedExecutor, or you instantiate theTransformListener
withspin_thread = True
.
BufferClient
doesn't have any TransformListener
. Also using MultiThreadedExecutor
does not work, you have to pass a ReentrantCallbackGroup
to the client inside the BufferClient
class -which currently is not exposed- as already mentioned in the issue.
This could be fixed by spinning a separate callback group in a separate thread. Independent execution of callback groups is currently only supported in rclcpp, but this pr aimed at implementing them https://github.com/ros2/rclpy/pull/909. TF2 also features a not so clean fix. You can pass the TransformListener a newly created node object. This new node is used to gather the transforms in parallel if you also set spin_thread to True.
I think there is a misunderstanding here. The issue described in this thread refers to the BufferClient
class which has nothing to do with a TransformListener
. The BufferClient
is just wrapping a rclpy.action.client.ActionClient
to call a tf2_ros buffer_server
using that client.
Oh nvm. I missread this.
I do have the same problem right now. Do I really need to change the BufferClient Interface or is there an other way of handling this issue?
Hi all, thanks very much for your input. I ran into this issue and I've found a solution that doesn't require changing the BufferClient interface, though I do think this should be changed. @clalancette is there any progress on this? A quick and dirty way is to change the Node's default callback group to a ReentrantCallbackGroup() then using a multithreaded excecutor to run the node. This way when you create the BufferClient it will use a ReentrantCallbackGroup by default. Some example code below:
class ExampleActionServer(Node):
def __init__(self):
super().__init__('example_action_server')
# Set the nodes default callback group to ReentrantCallbackGroup()
self._default_callback_group = ReentrantCallbackGroup()
self.tf_buffer = BufferClient(self, "/tf_action")
self.tf_buffer.action_client.wait_for_server(5.0)
self._action_server = ActionServer(
self,
ExampleAction,
'example_action',
self.execute_callback)
def main():
rclpy.init()
excecutor = rclpy.executors.MultiThreadedExecutor()
example_action_server = ExampleActionServer()
excecutor.add_node(example_action_server)
excecutor.spin()
I've found that the buffer client does work from a callback this way.
This blog is quite relevant for this issue to better understand it; https://karelics.fi/deadlocks-in-rclpy/
I would propose to the maintainers to put the service client of the BufferClient in a separate callback group, like is done for the subscribers of the transform listener
For people running into this problem:
Setting spin_thread
to true
did not fix my problem of doing transform
lookups within a callback. Adding a rclpy.executors.MultiThreadedExecutor
did.
Also, for people that have timeout/blocking issues in ROS2 in general, the multithreaded executor helps. But keep in mind that the default callback group is mutually exclusive and you need to select a reentrant callback group (or multiple mutually exclusive ones) for the involved callbacks to use multiple threads in the multithreaded executor.
Bug report
Required Info:
Steps to reproduce issue
Calling
BufferClient.lookup_transform
always timeouts although if I call the buffer server via ros2 cli it works.Create a node like the following:
Make sure the buffer server is already running and there is a valid transform between map->odom. Then publish to the topic that calls
BufferClient.lookup_transform
.The traceback is:
Expected behavior
It shouldn't crash since it works with the ros2 cli. If you use the following it works:
Actual behavior
It timeouts every time.
Additional notes
I modified https://github.com/ros2/geometry2/blob/ros2/tf2_ros_py/tf2_ros/buffer_client.py#L61 to accept also a callback group that is passed to the
ActionClient
. Then, in theTestNode
example above I set theself.cb_group=ReentrantCallbackGroup()
and the executor to be aMultiThreadedExecutor
. Only that way it works.I am missing something?