ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

If I understand your question, you'd like to have a service call an action and send the response for the service when the action goal is finished.

Ideally, we could wait on the futures related to the action client inside the service callback, but we currently can't spin from inside a callback so that's not an option.

The only method I can think of would be to use a flag to signal when the action is done and check it in the service callback. To illustrate, here is a crude example:


import time
from threading import Lock

from example_interfaces.srv import AddTwoInts
from example_interfaces.action import Fibonacci

import rclpy
from rclpy.action import ActionClient
from rclpy.node import Node
from rclpy.callback_groups import ReentrantCallbackGroup
from rclpy.executors import MultiThreadedExecutor


class ActionFromService(Node):

    def __init__(self):
        super().__init__('action_from_service')
        self.action_done_lock = Lock()
        self.action_done = False

        self.callback_group = ReentrantCallbackGroup()
        self.action_client = ActionClient(
            self, Fibonacci, 'fibonacci', callback_group=self.callback_group)
        self.srv = self.create_service(
            AddTwoInts,
            'add_two_ints',
            self.add_two_ints_callback,
            callback_group=self.callback_group)

    def feedback_callback(self, feedback):
        self.get_logger().info('Received feedback: {0}'.format(feedback.feedback.sequence))

    def add_two_ints_callback(self, request, response):
        self.get_logger().info('Request received: {} + {}'.format(request.a, request.b))
        if not self.action_client.wait_for_server(timeout_sec=5.0):
            self.get_logger().error('No action server available')
            return response

        response.sum = request.a + request.b

        goal = Fibonacci.Goal()
        goal.order = response.sum

        with self.action_done_lock:
            self.action_done = False

        send_goal_future = self.action_client.send_goal_async(
            goal, feedback_callback=self.feedback_callback)
        send_goal_future.add_done_callback(self.goal_response_callback)

        # Wait for action to be done
        while not self.action_done:
            time.sleep(0.1)

        return response

    def goal_response_callback(self, future):
        goal_handle = future.result()
        get_result_future = goal_handle.get_result_async()
        get_result_future.add_done_callback(self.get_result_callback)

    def get_result_callback(self, future):
        # Signal that action is done
        with self.action_done_lock:
            self.action_done = True


def main(args=None):
    rclpy.init(args=args)

    action_from_service = ActionFromService()

    executor = MultiThreadedExecutor()
    rclpy.spin(action_from_service, executor)

    rclpy.shutdown()


if __name__ == '__main__':
    main()

Note, I'm using a MultiThreadedExecutor and a ReentrantCallbackGroup so that we can process the service request and action callbacks in parallel. I've not included any error checking related to the action callbacks. Hopefully this example is close to what you want to do.

If I understand your question, you'd like to have a service call an action and send the response for the service when the action goal is finished.

Ideally, we could wait on the futures related to the action client inside the service callback, but we currently can't spin from inside a callback so that's not an option.

The only method I can think of would be to use a flag to signal when the action is done and check it in the service callback. To illustrate, here is a crude example:


import time
from threading import Lock
Event

from example_interfaces.srv import AddTwoInts
from example_interfaces.action import Fibonacci

import rclpy
from rclpy.action import ActionClient
from rclpy.node import Node
from rclpy.callback_groups import ReentrantCallbackGroup
from rclpy.executors import MultiThreadedExecutor


class ActionFromService(Node):

    def __init__(self):
        super().__init__('action_from_service')
        self.action_done_lock = Lock()
        self.action_done = False
self.action_done_event = Event()

        self.callback_group = ReentrantCallbackGroup()
        self.action_client = ActionClient(
            self, Fibonacci, 'fibonacci', callback_group=self.callback_group)
        self.srv = self.create_service(
            AddTwoInts,
            'add_two_ints',
            self.add_two_ints_callback,
            callback_group=self.callback_group)

    def feedback_callback(self, feedback):
        self.get_logger().info('Received feedback: {0}'.format(feedback.feedback.sequence))

    def add_two_ints_callback(self, request, response):
        self.get_logger().info('Request received: {} + {}'.format(request.a, request.b))
        if not self.action_client.wait_for_server(timeout_sec=5.0):
            self.get_logger().error('No action server available')
            return response

        response.sum = request.a + request.b

        goal = Fibonacci.Goal()
        goal.order = response.sum

        with self.action_done_lock:
            self.action_done = False
self.action_done_event.clear()

        send_goal_future = self.action_client.send_goal_async(
            goal, feedback_callback=self.feedback_callback)
        send_goal_future.add_done_callback(self.goal_response_callback)

        # Wait for action to be done
        while not self.action_done:
            time.sleep(0.1)
self.action_done_event.wait()

        return response

    def goal_response_callback(self, future):
        goal_handle = future.result()
        get_result_future = goal_handle.get_result_async()
        get_result_future.add_done_callback(self.get_result_callback)

    def get_result_callback(self, future):
        # Signal that action is done
        with self.action_done_lock:
            self.action_done = True
self.action_done_event.set()


def main(args=None):
    rclpy.init(args=args)

    action_from_service = ActionFromService()

    executor = MultiThreadedExecutor()
    rclpy.spin(action_from_service, executor)

    rclpy.shutdown()


if __name__ == '__main__':
    main()

Note, I'm using a MultiThreadedExecutor and a ReentrantCallbackGroup so that we can process the service request and action callbacks in parallel. I've not included any error checking related to the action callbacks. Hopefully this example is close to what you want to do.

Edit: I've updated the example to use threading.Event().