rclpy icon indicating copy to clipboard operation
rclpy copied to clipboard

Using rclpy.spin_once and await in a coroutine causes busy waiting

Open bjsowa opened this issue 11 months ago • 1 comments

I noticed that when an executor is executing a coroutine which called await, all calls to rclpy.spin_once end immediately, causing busy waiting which results in 100% CPU consumption. Here's a script that demonstrates this issue:

import rclpy
import rclpy.logging
from rclpy.task import Future
from rclpy.executors import SingleThreadedExecutor
from rclpy.node import Node

async def coroutine():
    print("Coroutine")
    future = Future()
    await future

rclpy.init()
rclpy.logging.set_logger_level("rcl", rclpy.logging.LoggingSeverity.DEBUG)
node = Node("test_node")
node.get_logger().set_level(rclpy.logging.LoggingSeverity.DEBUG)
node.create_timer(1.0, coroutine)

# This causes busy waiting
while rclpy.ok():
    rclpy.spin_once(node)

# # This does not
# rclpy.spin(node)

# # This does not either
# executor = SingleThreadedExecutor()
# executor.add_node(node)
# while rclpy.ok():
#     executor.spin_once()

node.destroy_node()
rclpy.shutdown()

Tried it in Humble, Iron, Jazzy and Rolling, getting the same result every time.

I suspect the issue might be with the way the __async__ method in Future objects is implemented: https://github.com/ros2/rclpy/blob/rolling/rclpy/rclpy/task.py#L73-L77

bjsowa avatar Jan 26 '25 03:01 bjsowa

@sloretz could you take a look when you get a chance? 🧇

Yadunund avatar Feb 06 '25 21:02 Yadunund