Skip to content
Closed
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 5 additions & 1 deletion rclpy/rclpy/task.py
Original file line number Diff line number Diff line change
Expand Up @@ -212,6 +212,7 @@ def __init__(self, handler, args=None, kwargs=None, executor=None):
self._handler = handler(*args, **kwargs)
self._args = None
self._kwargs = None
self._future = None
# True while the task is being executed
self._executing = False
# Lock acquired to prevent task from executing in parallel with itself
Expand All @@ -236,7 +237,10 @@ def __call__(self):
if inspect.iscoroutine(self._handler):
# Execute a coroutine
try:
self._handler.send(None)
if self._future is None or self._future.done():
if self._future and self._future.exception():
raise self._future.exception()
self._future = self._handler.send(None)
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't think this can assume a coroutine will return a future. It seems like the behavior is specific to the async library being used (see #962 (comment)). This change is interesting though because it seems like it would both satisfy an rclpy.Future by calling send(None) until it raised StopIteration, and would only call asyncio.Future.__await__ once.

It still needs a way to wake the executor when an asyncio future completes, and given that asyncio isn't thread safe I bet there would be problems if a multithreaded executor was used.

except StopIteration as e:
# The coroutine finished; store the result
self._handler.close()
Expand Down