Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Check if Task(Future) is canceled. (backport #1377) #1403

Open
wants to merge 3 commits into
base: humble
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 2 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
20 changes: 16 additions & 4 deletions rclpy/rclpy/executors.py
Original file line number Diff line number Diff line change
Expand Up @@ -299,15 +299,25 @@ def spin_until_future_complete(self, future: Future, timeout_sec: float = None)
future.add_done_callback(lambda x: self.wake())

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)
while (
self._context.ok()
and not future.done()
and not future.cancelled()
and not self._is_shutdown
):
self._spin_once_until_future_complete(future, timeout_sec)
else:
start = time.monotonic()
end = start + timeout_sec
timeout_left = TimeoutObject(timeout_sec)

while self._context.ok() and not future.done() and not self._is_shutdown:
self.spin_once_until_future_complete(future, timeout_left)
while (
self._context.ok()
and not future.done()
and not future.cancelled()
and not self._is_shutdown
):
self._spin_once_until_future_complete(future, timeout_left)
now = time.monotonic()

if now >= end:
Expand Down Expand Up @@ -500,6 +510,8 @@ def _wait_for_ready_callbacks(
with self._tasks_lock:
# Get rid of any tasks that are done
self._tasks = list(filter(lambda t_e_n: not t_e_n[0].done(), self._tasks))
# Get rid of any tasks that are cancelled
self._tasks = list(filter(lambda t_e_n: not t_e_n[0].cancelled(), self._tasks))

# Gather entities that can be waited on
subscriptions: List[Subscription] = []
Expand Down
54 changes: 37 additions & 17 deletions rclpy/rclpy/task.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from enum import Enum
import inspect
import sys
import threading
Expand All @@ -24,14 +25,19 @@ def _fake_weakref():
return None


class FutureState(Enum):
"""States defining the lifecycle of a future."""

PENDING = 'PENDING'
CANCELLED = 'CANCELLED'
FINISHED = 'FINISHED'


class Future:
"""Represent the outcome of a task in the future."""

def __init__(self, *, executor=None):
# true if the task is done or cancelled
self._done = False
# true if the task is cancelled
self._cancelled = False
self._state = FutureState.PENDING
# the final return value of the handler
self._result = None
# An exception raised by the handler when called
Expand All @@ -53,15 +59,20 @@ def __del__(self):

def __await__(self):
# Yield if the task is not finished
while not self._done:
while self._pending():
yield
return self.result()

def _pending(self):
return self._state == FutureState.PENDING

def cancel(self):
"""Request cancellation of the running task if it is not done already."""
with self._lock:
if not self._done:
self._cancelled = True
if not self._pending():
return

self._state = FutureState.CANCELLED
self._schedule_or_invoke_done_callbacks()

def cancelled(self):
Expand All @@ -71,7 +82,7 @@ def cancelled(self):
:return: True if the task was cancelled
:rtype: bool
"""
return self._cancelled
return self._state == FutureState.CANCELLED

def done(self):
"""
Expand All @@ -80,7 +91,7 @@ def done(self):
:return: True if the task is finished or raised while it was executing
:rtype: bool
"""
return self._done
return self._state == FutureState.FINISHED

def result(self):
"""
Expand Down Expand Up @@ -111,8 +122,8 @@ def set_result(self, result):
"""
with self._lock:
self._result = result
self._done = True
self._cancelled = False
self._state = FutureState.FINISHED

self._schedule_or_invoke_done_callbacks()

def set_exception(self, exception):
Expand All @@ -124,8 +135,8 @@ def set_exception(self, exception):
with self._lock:
self._exception = exception
self._exception_fetched = False
self._done = True
self._cancelled = False
self._state = FutureState.FINISHED

self._schedule_or_invoke_done_callbacks()

def _schedule_or_invoke_done_callbacks(self):
Expand Down Expand Up @@ -173,7 +184,7 @@ def add_done_callback(self, callback):
"""
invoke = False
with self._lock:
if self._done:
if not self._pending():
executor = self._executor()
if executor is not None:
executor.create_task(callback, self)
Expand Down Expand Up @@ -226,10 +237,14 @@ def __call__(self):

The return value of the handler is stored as the task result.
"""
if self._done or self._executing or not self._task_lock.acquire(blocking=False):
if (
not self._pending() or
self._executing or
not self._task_lock.acquire(blocking=False)
):
return
try:
if self._done:
if not self._pending():
return
self._executing = True

Expand All @@ -239,7 +254,6 @@ def __call__(self):
self._handler.send(None)
except StopIteration as e:
# The coroutine finished; store the result
self._handler.close()
self.set_result(e.value)
self._complete_task()
except Exception as e:
Expand Down Expand Up @@ -271,3 +285,9 @@ def executing(self):
:rtype: bool
"""
return self._executing

def cancel(self) -> None:
if self._pending() and inspect.iscoroutine(self._handler):
self._handler.close()

super().cancel()
20 changes: 20 additions & 0 deletions rclpy/test/test_executor.py
Original file line number Diff line number Diff line change
Expand Up @@ -225,6 +225,26 @@ async def coroutine():
self.assertTrue(future.done())
self.assertEqual('Sentinel Result', future.result())

def test_create_task_coroutine_cancel(self) -> None:
self.assertIsNotNone(self.node.handle)
executor = SingleThreadedExecutor(context=self.context)
executor.add_node(self.node)

async def coroutine():
return 'Sentinel Result'

future = executor.create_task(coroutine)
self.assertFalse(future.done())
self.assertFalse(future.cancelled())

future.cancel()
self.assertTrue(future.cancelled())

executor.spin_until_future_complete(future)
self.assertFalse(future.done())
self.assertTrue(future.cancelled())
self.assertEqual(None, future.result())

def test_create_task_normal_function(self):
self.assertIsNotNone(self.node.handle)
executor = SingleThreadedExecutor(context=self.context)
Expand Down
33 changes: 33 additions & 0 deletions rclpy/test/test_task.py
Original file line number Diff line number Diff line change
Expand Up @@ -322,6 +322,39 @@ def cb(fut):
f.add_done_callback(cb)
assert called

def test_set_result_on_done_future_without_exception(self) -> None:
f = Future()
f.set_result(None)
self.assertTrue(f.done())
self.assertFalse(f.cancelled())
f.set_result(None)
self.assertTrue(f.done())
self.assertFalse(f.cancelled())

def test_set_result_on_cancelled_future_without_exception(self) -> None:
f = Future()
f.cancel()
self.assertTrue(f.cancelled())
self.assertFalse(f.done())
f.set_result(None)
self.assertTrue(f.done())

def test_set_exception_on_done_future_without_exception(self) -> None:
f = Future()
f.set_result(None)
self.assertIsNone(f.exception())
f.set_exception(Exception())
f.set_result(None)
self.assertIsNotNone(f.exception())

def test_set_exception_on_cancelled_future_without_exception(self) -> None:
f = Future()
f.cancel()
self.assertTrue(f.cancelled())
self.assertIsNone(f.exception())
f.set_exception(Exception())
self.assertIsNotNone(f.exception())


if __name__ == '__main__':
unittest.main()