rclpy
rclpy copied to clipboard
SingleThreadedExecutor spin_once_until_future_complete does not spin until future is complete
Bug report
Required Info:
- Operating System:
- Ubuntu 20.04.2 LTS
- Installation type:
- Binary
- Version or commit hash:
- Galactic (code looks the same in Rolling)
- DDS implementation:
- Galactic default
- Client library (if applicable):
- rclpy
Steps to reproduce issue
Call a service twice from a python node with a SingleThreadedExecutor like this:
future = my_service_client.call_async(req)
executor.spin_once_until_future_complete(future)
res = future.result()
Expected behavior
First time the res.done() == True
, the second time res.done() == True
.
Actual behavior
First time the res.done() == True
, the second time res.done() == False
.
Additional information
The implementation here looks strange to me https://github.com/ros2/rclpy/blob/fb1058935f25f20a5ba9552994b9b63a3edd36f9/rclpy/rclpy/executors.py#L727
If I replace:
executor.spin_once_until_future_complete(future)
with
while not future.done():
executor.spin_once()
my example works as expected. Should there not be a loop that waits to see if the future is complete? What do you think? How come it works the first time I call the service and not the second time I call the service?
related to https://github.com/ros2/rclpy/issues/989?
my example works as expected. Should there not be a loop that waits to see if the future is complete?
No i do not think so, that does not seem to be the intention of this method.
No i do not think so, that does not seem to be the intention of this method.
But for the MultiThreadedExecutor there is a wait_condition
on future.done https://github.com/ros2/rclpy/blob/fb1058935f25f20a5ba9552994b9b63a3edd36f9/rclpy/rclpy/executors.py#L782
@ErikOrjehag i mean that your expectation is correct, this seems to be a bug for me. sorry for the confusion 😅
Can this be related to the inexistence of the Executor when the Future class is created? Since when I check for future.done() the process freeze up