Skip to content

Commit

Permalink
Cancelling asynchronous tasks has no effect?
Browse files Browse the repository at this point in the history
  ros2/rclpy#1099

Signed-off-by: Tomoya Fujita <[email protected]>
  • Loading branch information
fujitatomoya committed Nov 7, 2024
1 parent bdd3410 commit fb33e32
Show file tree
Hide file tree
Showing 3 changed files with 88 additions and 0 deletions.
2 changes: 2 additions & 0 deletions prover_rclpy/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,8 @@
'rclpy_1046 = src.rclpy_1046:main',
'rclpy_1047 = src.rclpy_1047:main',
'rclpy_1098 = src.rclpy_1098:main',
'rclpy_1099 = src.rclpy_1099:main',
'rclpy_1099_2 = src.rclpy_1099_2:main',
'rclpy_1132 = src.rclpy_1132:main',
'rclpy_1149 = src.rclpy_1149:main',
'rclpy_1159 = src.rclpy_1159:main',
Expand Down
52 changes: 52 additions & 0 deletions prover_rclpy/src/rclpy_1099.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@

import rclpy
from rclpy.node import Node
from rclpy.task import Future
from rclpy.callback_groups import MutuallyExclusiveCallbackGroup


def sleep_async(node: Node, time: float) -> Future:
"""
Sleeps for a given amount of time.
Creates a timer with the sleep time as frequency and destroys it on the first callback.
args:
node: The node to sleep on. Future will be created with the nodes executor.
time: The time to sleep in seconds
returns:
A future that will be done after the given amount of time.
"""
future = Future(executor=node.executor)
timer = node.create_timer(timer_period_sec=time, callback=lambda: _timer_callback(future), callback_group=MutuallyExclusiveCallbackGroup())

def _timer_callback(future: Future):
future.set_result(None)
node.destroy_timer(timer)

return future

async def sleep(self, seconds):
for i in range(1, seconds+1):
await sleep_async(self, 1)
print(f"Slept for {i} seconds")


def main(args=None):
rclpy.init()

node = rclpy.create_node("test")
executor = rclpy.get_global_executor()
executor.add_node(node)
task = executor.create_task(sleep, node, 5)

task.cancel()
print(f"{task.cancelled()=}")
executor.spin_until_future_complete(task)

print(f"{task.done()=}")
print(f"{task.cancelled()=}")

if __name__ == '__main__':
main()
34 changes: 34 additions & 0 deletions prover_rclpy/src/rclpy_1099_2.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
import rclpy


async def test_cancel():
future = rclpy.task.Future()
future.cancel()

print(future, future.cancelled(), future.done())

return await future


def main(args=None):
rclpy.init()

node = rclpy.create_node("test")

def timer_callback():
node.get_logger().info("Logging timer fired.")

node.create_timer(1.0, timer_callback)

executor = rclpy.get_global_executor()
executor.add_node(node)
task = executor.create_task(test_cancel)

print(f"{task.cancelled()=}")
#task.cancel()
executor.spin_until_future_complete(task)
print(f"{task.done()=}")
print(f"{task.cancelled()=}")

if __name__ == '__main__':
main()

0 comments on commit fb33e32

Please sign in to comment.