rclpy
rclpy copied to clipboard
Timer not executing when created from within a task
Bug report
When using spin_until_future_complete
with a task that await
on a future set in a timer, the future is never completed. Interestingly, this only happens when setting a timeout on spin_until_future_complete
, if a timeout is not provided, or if None
is provided, then the task completes successfully.
Required Info:
- Operating System:
- ubuntu22.04
- Installation type:
- Binary
- Version or commit hash:
- 3.3.4-1jammy.20220620.181239
- DDS implementation:
- default
- Client library (if applicable):
- rclpy
Steps to reproduce issue
import rclpy
import rclpy.node
import rclpy.executors
rclpy.init()
node = rclpy.node.Node("test_node")
executor = rclpy.executors.SingleThreadedExecutor()
executor.add_node(node)
fut = rclpy.Future()
async def work():
node.create_timer(0.1, lambda: fut.set_result(True))
await fut
task = executor.create_task(work())
executor.spin_until_future_complete(task, 1) # works when timeout is None
print(task.done())
rclpy.shutdown()
Expected behavior
Future is completed
Actual behavior
Future is not completed
Additional information
Looking at the code of spin_until_future_complete
, it behaves differently depending on if a timeout is provided.
if timeout_sec is None or timeout_sec < 0:
while self._context.ok() and not future.done() and not self._is_shutdown:
self.spin_once_until_future_complete(future, timeout_sec)
else:
start = time.monotonic()
end = start + timeout_sec
timeout_left = timeout_sec
while self._context.ok() and not future.done() and not self._is_shutdown:
self.spin_once_until_future_complete(future, timeout_left)
now = time.monotonic()
if now >= end:
return
timeout_left = end - now
This all looks good but furthur investigation of wait_for_ready_callbacks
(which is eventually called later down the chain),
while True:
if self._cb_iter is None or self._last_args != args or self._last_kwargs != kwargs:
# Create a new generator
self._last_args = args
self._last_kwargs = kwargs
self._cb_iter = self._wait_for_ready_callbacks(*args, **kwargs)
try:
return next(self._cb_iter)
except StopIteration:
# Generator ran out of work
self._cb_iter = None
It creates a new generator whenever _last_args
or _last_kwargs
is different, the "timeout" path of spin_until_future_complete
does exactly that, each spin_once_until_future_complete
is passed a different timeout.
My guess is that somehow creating new generators every "tick" causes new "work" to be created, and executing a "work" causes a new generator to be created, resulting in a infinite list of pending "work", which causes the actual task to never be executed.
I also notice that when adding a print
statement to Future.__await__()
, the same future is being yielded endlessly very quickly.
def __await__(self):
# Yield if the task is not finished
while not self._done:
print(id(self), "yielding")
yield
return self.result()
output
139875185274560 yielding
139875185274560 yielding
139875185274560 yielding
139875185274560 yielding
139875185274560 yielding
139875185274560 yielding
139875185274560 yielding
... thousands of lines
I think this is bug described in issue header.
It will create generater based on the pending task for each iteration on _wait_for_ready_callbacks
.
https://github.com/ros2/rclpy/blob/6c0847a70df2a359c28ffae7e49ece2e62c1794d/rclpy/rclpy/executors.py#L483-L492