You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
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:
importrclpyimportrclpy.loggingfromrclpy.taskimportFuturefromrclpy.executorsimportSingleThreadedExecutorfromrclpy.nodeimportNodeasyncdefcoroutine():
print("Coroutine")
future=Future()
awaitfuturerclpy.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 waitingwhilerclpy.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 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: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
The text was updated successfully, but these errors were encountered: