Closed jpfeltracco closed 3 months ago
The related code is
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 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()
?
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
closing this, https://github.com/ros2/rclpy/pull/1304 completed.
Bug report
Required Info:
Steps to reproduce issue
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)