0
$\begingroup$

Rosanswers logo

Hi, I have node written in Python which is a service server. Service's callback is sending goal to action server (action that commands industrial robot to move). After successful move (robot on desired gola) the service should response with some information about robot (like data from force/torque sensor i.e.). The concept is simple (you can imagine that's a step method from openai gym).

The node is based on example from link text. However, the service is responding much quicker then action. I tried using threading.Event() but node freezes at event.wait(). How can I wait for action using async conecpt?

Greg


Originally posted by souphis on ROS Answers with karma: 13 on 2019-05-09

Post score: 1

$\endgroup$

1 Answer 1

0
$\begingroup$

Rosanswers logo

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 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_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

        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
        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
        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().


Originally posted by jacobperron with karma: 1870 on 2019-06-05

This answer was ACCEPTED on the original site

Post score: 5


Original comments

Comment by souphis on 2019-06-05:
Thank you very much! That's exactly what I was looking for. Can you give me some advice how can I learn such advance tricks in ROS2?

Comment by jacobperron on 2019-06-05:
As the original author of Actions in rclpy, I have a more intimate understanding. I think we are severely lacking in tutorials and documentation that we'll hopefully improve in the near future. Recently, we now have some new tutorials on Actions that are more involved, e.g. https://index.ros.org/doc/ros2/Tutorials/Actions/Writing-an-Action-Client-Python/. There's some minimal API docs on rclpy executors and callback groups, but I believe we plan to have more user-friendly tutorials eventually.

Generally, asking questions on ROS Answers (as you have done!), looking at the demos and examples, and experimenting are good ways to learn new things :)

Comment by lpz_njames on 2020-05-19:
Jacob, thanks. I adapted this to call one service from the callback of another.

Comment by galaxee on 2020-12-09:
@jacobperron, just wanted to check.... you mentioned that at the time of answering you couldn't spin from inside a callback... is that still the case? Should I use approximately the same code if I'm calling an action from another action?

Comment by jacobperron on 2020-12-09:
@galaxee That is still the case AFAIK.

Comment by galaxee on 2020-12-09:
@jacobperron Thanks! Sorry if this is a dumb question, but is the wait blocking? Does this mean that ActionFromService can't process another request? Is there any way to avoid the blocking?

Comment by jacobperron on 2020-12-09:
Yes, the "wait" the example above is blocking (which is on purpose to answer the original question). But you don't necessarily have to wait and are free to restructure your code as you want. Note, since the example is using a MultiThreadedExecutor, the code should still process multiple service requests asynchronously (though I haven't confirmed myself).

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.