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

A less-asyncronous way of using ROS2 action clients?

asked 2021-04-28 17:36:22 -0500

masynthetic gravatar image

Hello, I am a little while into developing my first ROS2 project as someone totally new to ROS. My last couple of posts may provide some useful context of how I arrived at this issue but essentially my 'robot' has a set of actions and services for reading sensors or operating actuators, and then I use nodes without a real defined ROS type (such as client) which I have been calling 'drivers' to then put all the needed clients and subscribers needed to perform an operation into. I like this design because by just using some additional protocol within the server to identify the clients it is fairly easy to control access so that multiple drivers(clients) can use the same service or action in a coordinated manner as not to conflict. I am not sure if there's any issues with this approach, I would be happy to hear them, but it just seemed like the best approach I could come up with on my own.

This is working just fine when it comes to service clients in the 'drivers' but I am looking for a 'less-asynchronous' way of using the action clients than what the tutorial demonstrates, using something like the spin_until_future_complete method but I have not been successful in getting the response back.

The operation would look something like this:

1) move to position 1 (action)

2) read a set of 3 sensors and post to topics (services)

3) move to position 2 (action)

4) read sensors again, etc...

so I do not need to do anything in this node while the action is happening, just wait for it to finish. Using service clients it looks something like this:

    # set light level
def set_light(self, light_number, power_level):
    # create service request
    request = LightSet.Request()
    request.light_number = light_number
    request.power_level = power_level
    request.driver_status = self.driver_status

    # send request
    future = self.set_light_client.call_async(request)
    # recieve response
    rclpy.spin_until_future_complete(self.set_light_node, future)
    # processing
    if(future.result() is not None):
        result: LightSet.Response = future.result()
        if(result.success):
            self.get_logger().info('light {} set to {}'.format(light_number, result.confirm_level))
        else:
            self.get_logger().error('light setting failed')
    else:
        self.get_logger().error('light service call failed: {}'.format(future.exception()))

and my interpretation of using action clients in this manner has looked something like this but it does not work as I can only seem get ClientGoalHandle objects back and not the actual response

    # move to target
def move_to_target(self, target):
    # send goal to move x action server
    # create goal
    goal_msg = AxisControl.Goal()
    goal_msg.driver_status = self.driver_status
    goal_msg.target = target
    # wait
    self.move_x_client.wait_for_server()
    # send request
    future = self.move_x_client.send_goal_async(goal_msg)
    # recieve response
    rclpy.spin_until_future_complete(self.move_x_node, future)
    # process response
    if future.result() is not None:
        # self.get_logger().info(future.result)
        result: AxisControl.Result() = future.result().result
        if(result.complete):
            self.get_logger().info('move finished')
            return True
        else:
            self.get_logger().info('move failed')
            return False

Using the callback based approach everything seems to work OK but I am just finding it to be much more of a ... (more)

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
2

answered 2021-05-03 13:50:03 -0500

synaptic gravatar image

updated 2021-05-03 20:47:11 -0500

I found the following way using asynchronous callbacks modified from the docs:

import rclpy
from rclpy.action import ActionClient
from rclpy.node import Node

from action_msgs.msg import GoalStatus
from action_tutorials_interfaces.action import Fibonacci


class FibonacciActionClient(Node):

    def __init__(self):
        super().__init__('fibonacci_action_client')
        self._action_client = ActionClient(self, Fibonacci, 'fibonacci')
        self.status = GoalStatus.STATUS_EXECUTING

    def send_goal(self, order):
        self.status = GoalStatus.STATUS_EXECUTING
        goal_msg = Fibonacci.Goal()
        goal_msg.order = order

        self._action_client.wait_for_server()

        self._send_goal_future = self._action_client.send_goal_async(goal_msg, feedback_callback=self.feedback_callback)

        self._send_goal_future.add_done_callback(self.goal_response_callback)

    def goal_response_callback(self, future):
        goal_handle = future.result()
        if not goal_handle.accepted:
            self.get_logger().info('Goal rejected :(')
            return

        self.get_logger().info('Goal accepted :)')

        self._get_result_future = goal_handle.get_result_async()
        self._get_result_future.add_done_callback(self.get_result_callback)

    def get_result_callback(self, future):
        result = future.result().result
        self.get_logger().info('Result: {0}'.format(result.sequence))
        self.status = GoalStatus.STATUS_SUCCEEDED

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


def main(args=None):
    rclpy.init(args=args)
    action_client = FibonacciActionClient()
    action_client.send_goal(10)

    while action_client.status != GoalStatus.STATUS_SUCCEEDED:
        rclpy.spin_once(action_client)

    action_client.get_logger().info('All done!')
    action_client.destroy_node()

if __name__ == '__main__':
    main()

You can also use this method to make successive calls to action_client.send_goal() and it will wait until each goal is done before the next goal is called. You just have to have the while loop inside the for loop, i.e:

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

    goals = [10, 11, 12, 13, 14, 15]

    for goal in goals:

        action_client.send_goal(goal)

        while action_client.status != GoalStatus.STATUS_SUCCEEDED:
            rclpy.spin_once(action_client)

    action_client.get_logger().info('All done!')
    action_client.destroy_node()
edit flag offensive delete link more

Comments

thanks a lot for your answer! I think this is exactly what I am looking for, I will work on integrating it

masynthetic gravatar image masynthetic  ( 2021-05-03 22:30:00 -0500 )edit
3

answered 2021-04-29 13:45:05 -0500

updated 2021-04-29 13:47:29 -0500

I feel your pain, the fact that there isn't a simpler wrapper for actions and services for "synchronous" use-cases I think will be a challenge for many users. Luckily, in Nav2 we've been working on some simple wrappers for our own internal use that can be leveraged in other packages.

https://github.com/ros-planning/navig...

This gives you a much more Simple Service Client interface (rather than dealing with nasty futures and such). Just create the object and call invoke with your request and returns the response. There's also a wait function to make sure its online, but otherwise handles the rest for you.

We unfortunately don't have a Simple Action Client at the moment, but I'd be more than happy to merge in one in the nav2_utils package that could be used by yourself and others in the future to help fill that niche. One way to get a "simpler" call though rather than spinning is to leverage the SendGoalOptions class:

  auto send_goal_options = rclcpp_action::Client<ClientT>::SendGoalOptions();
  send_goal_options.result_callback =
    std::bind(&WaypointFollower::resultCallback, this, std::placeholders::_1);
  send_goal_options.goal_response_callback =
    std::bind(&WaypointFollower::goalResponseCallback, this, std::placeholders::_1);
  future_goal_handle_ =
    nav_to_pose_client_->async_send_goal(client_goal, send_goal_options);

Whereas you can set callbacks for completion / goal acceptance / feedback rather than spinning until future complete. If the node you used to create the action client is just free spinning (or spin_some in some loop), then you don't need to worry too much about the async-ness, just wait for a callback result. Its still not as ideal as "send goal -> wait -> get result" blocking in the code, but its also probably not the best way to structure your software for an action (though I won't pretend I haven't done that myself).

Down the line, if there's interest, I'd be more than happy to move the Simple clients over to ROS2 client libraries directly. They really only live in Nav2 because we needed them so we built them.

edit flag offensive delete link more

Comments

Thanks so much for your thoughtful answer, I would most definitely be interested in a simpler action wrapper if it were released. Just for clarification when you say 'free spinning' does this mean just constantly spinning from main rather than the start/stop method shown in my code?

masynthetic gravatar image masynthetic  ( 2021-05-03 22:33:49 -0500 )edit

Yes, that’s what I mean

stevemacenski gravatar image stevemacenski  ( 2021-05-04 12:28:16 -0500 )edit

Question Tools

5 followers

Stats

Asked: 2021-04-28 17:36:22 -0500

Seen: 1,510 times

Last updated: May 03 '21