ros2 / rclpy

rclpy (ROS Client Library for Python)
Apache License 2.0
289 stars 224 forks source link

Async tasks are processed in LIFO not FIFO #1303

Closed jpfeltracco closed 3 months ago

jpfeltracco commented 3 months ago

Bug report

Required Info:

Steps to reproduce issue

import rclpy
from rclpy.node import Node
from rclpy.executors import SingleThreadedExecutor

class SimpleNode(Node):
    def __init__(self, n=10):
        super().__init__('simple_node')
        self.n = n
        # Create a one-shot timer with a zero duration to start tasks after initialization
        self.timer = self.create_timer(0, self.start_tasks)

    def start_tasks(self):
        self.timer.cancel()
        # Scheduling tasks to print their execution order
        tasks = [self.executor.create_task(self.print_value(i)) for i in range(self.n)]

    async def print_value(self, value):
        print(f"Task executed with value: {value}")

def main(args=None):
    rclpy.init(args=args)
    node = SimpleNode()
    executor = SingleThreadedExecutor()
    executor.add_node(node)
    try:
        executor.spin()  # Spin the node to process callbacks
    except Exception as e:
        node.get_logger().error(f'Unhandled exception in executor: {e}')
    finally:
        executor.shutdown()
        node.destroy_node()

if __name__ == '__main__':
    main()

Expected behavior

1, 2, 3..., 9

Would expect output to be roughly 0->9. I understand no guarantees without awaiting explicitly, but generally would expect tasks created earlier in time should be scheduled for execution earlier in FIFO fashion. This matches how asyncio in base Python works.

Actual behavior

9, 8, 7, 6..., 0

Additional information

See this code snippet for how asyncio works (producing 0, 1, 2 ... 9)

import asyncio

async def print_value(value):
    # Simulate some asynchronous operation
    print(f"Task started with value: {value}")

async def main(n=10):
    for i in range(n):
        asyncio.create_task(print_value(i))
    # Give control to executor
    await asyncio.sleep(1)

# Run the main function with the default number of tasks
asyncio.run(main())
Barry-Xu-2018 commented 3 months ago

The related code is

https://github.com/ros2/rclpy/blob/8db266a79331f8b97f836c9ca963b8e0d647b457/rclpy/rclpy/executors.py#L572

I don't understand the purpose of using reversed() here.
This part of the code had been in place for a long time. It comes from this PR https://github.com/ros2/rclpy/pull/166.
@sloretz Do you remember why reversed() is used here?

sloretz commented 3 months ago

@sloretz Do you remember why reversed() is used here?

I don't remember why, and I don't see a reason for it. What happens if we remove reversed()?

fujitatomoya commented 3 months ago

What happens if we remove reversed()?

It processes the tasks in FIFO order, maybe just an easy oversight... https://github.com/ros2/rclpy/pull/1304 can fix this.

with https://github.com/fujitatomoya/ros2_test_prover/commit/cbbdaa3ace70e3a094d646e2b0dfc2122c63611e

root@tomoyafujita:~/ros2_ws/colcon_ws# ros2 run prover_rclpy rclpy_1303
Task executed with value: 9
Task executed with value: 8
Task executed with value: 7
Task executed with value: 6
Task executed with value: 5
Task executed with value: 4
Task executed with value: 3
Task executed with value: 2
Task executed with value: 1
Task executed with value: 0
root@tomoyafujita:~/ros2_ws/colcon_ws# ros2 run prover_rclpy rclpy_1303
Task executed with value: 0
Task executed with value: 1
Task executed with value: 2
Task executed with value: 3
Task executed with value: 4
Task executed with value: 5
Task executed with value: 6
Task executed with value: 7
Task executed with value: 8
Task executed with value: 9
fujitatomoya commented 3 months ago

closing this, https://github.com/ros2/rclpy/pull/1304 completed.