Skip to content

async service server callback gets stuck on wait set #1462

@JenniferBuehler

Description

@JenniferBuehler

Hello,

I have been debugging an issue which I encountered when trying to add a async service callback. What I want to achieve is a service callback which doesn't block the spinning (I have simplified the problem in the code below). Long story short: in the async service callback, I want to await an event.

I got it tracked down to that the executor gets stuck on wait_set.wait(..) in executors.py (line 685 on jazzy release):

                # Wait for something to become ready
                wait_set.wait(timeout_nsec)

I'm still lacking more knowledge of the executor's details to pinpoint where to keep digging. Before I dig further, I thought it might be worth asking if someone has a suggestion what the issue could be. It could make the process lots more time efficient - would greatly appreciate any input!

What's really curious (at least to my ignorant self) is the following: it works fine if I have a timed callback set up. Each time the timed callback gets called, the wait set gets "unstuck" for exactly two iterations, and my __await__ method gets called. This unblocks the process and the service call completes successfully. If you comment out the timed callback (self.create_timer(1, self.timer_callback)), the service call gets stuck.

This could be related to #1405 .

I tested this on jazzy (Ubuntu 24.04) and humble (Ubuntu 22.04).

Below is my test code, run with

python3 simple_coroutine_test.py

and the service call

ros2 service call /simple_trigger std_srvs/srv/Trigger "{}"
import rclpy
import time
from rclpy.node import Node
from std_srvs.srv import Trigger
from rclpy.callback_groups import ReentrantCallbackGroup, MutuallyExclusiveCallbackGroup


class AwaitCount:
    """Implements the await method which finishes once the method has been called a number of times."""
    def __init__(self, logger):
        self._logger = logger
        self._cnt = 0

    def __await__(self):
        while self._cnt < 10:
            # Yield control so the event loop can do other work (ROS spinning work)
            self._logger.info("Awaiting...")
            self._cnt += 1
            yield
        return  # Done waiting


class SimpleServiceNode(Node):
    """Simple test node for testing async service callback."""

    def __init__(self):
        super().__init__('simple_service_node')
        callback_group = MutuallyExclusiveCallbackGroup() # ReentrantCallbackGroup()

        # Create the service for the trigger request.
        self.create_service(Trigger, 'simple_trigger', self.trigger_callback, callback_group = callback_group)

        # Create a timer that logs a "heartbeat" - shows the ROS loop is still running and somehow
        # unblocks the service callback.
        self.create_timer(1, self.timer_callback)

    async def trigger_callback(self, request, response):
        """Callback for trigger service."""
        self.get_logger().info('Trigger called.')

        # Wait asynchronously (while allowing ROS to spin).
        await AwaitCount(self.get_logger())

        self.get_logger().info("Received result!")

        response.success = True
        response.message = "Finished test successfully."
        return response

    async def timer_callback(self):
        self.get_logger().info('Heartbeat: timer is alive.')

def main():
    rclpy.init()
    node = SimpleServiceNode()

    use_single = True  # set to True to use SingleThreadedExecutor, False for MultiThreadeExecutor
    try:
        if use_single:
            rclpy.spin(node)
        else:
            executor = rclpy.executors.MultiThreadedExecutor(num_threads=2)
            executor.add_node(node)
            executor.spin()
    except KeyboardInterrupt:
        pass

if __name__ == '__main__':
    main()

Metadata

Metadata

Assignees

Labels

No labels
No labels

Type

No type

Projects

No projects

Milestone

No milestone

Relationships

None yet

Development

No branches or pull requests

Issue actions