Edit on Github

Writing an Action Client (Python)

In this tutorial, we look at implementing an action client in Python.

Make sure you have satisfied all prerequisites.

Sending a Goal

Let’s get started!

To keep things simple, we’ll scope this tutorial to a single file. Open a new file, let’s call it fibonacci_action_client.py, and add the following boilerplate code:

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
14
15
16
17
18
import rclpy
from rclpy.node import Node


class FibonacciActionClient(Node):

    def __init__(self):
        super().__init__('fibonacci_action_client')


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

    action_client = FibonacciActionClient()


if __name__ == '__main__':
    main()

We’ve defined a class FibonacciActionClient that is a subclass of Node. The class is initialized by calling the Node constructor, naming our node “fibonacci_action_client”:

        super().__init__('fibonacci_action_client')

After the class definition, we define a function main() that initializes ROS and creates an instance of our FibonacciActionClient node. Finally, we call main() in the entry point of our Python program.

You can try running the program:

# Linux/OSX
python3 fibonacci_action_client.py
# Windows
python fibonacci_action_client.py

It doesn’t do anything interesting…yet.

Let’s import and create an action client using the custom action definition from the previous tutorial on Creating an Action.

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
import rclpy
from rclpy.action import ActionClient
from rclpy.node import Node

from action_tutorials.action import Fibonacci


class FibonacciActionClient(Node):

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

At line 12 we create an ActionClient by passing it three arguments:

  1. a ROS node to add the action client to: self.

  2. the type of the action: Fibonacci.

  3. the action name: 'fibonacci'.

Our action client will be able to communicate with action servers of the same action name and type.

Now let’s tell the action client to send a goal. Add a new method send_goal():

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
class FibonacciActionClient(Node):

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

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

        self._action_client.wait_for_server()

        self._action_client.send_goal_async(goal_msg)

We create a new Fibonacci goal message and assign a sequence order. Before sending the goal message, we must wait for an action server to become available. Otherwise, a potential action server may miss the goal we’re sending.

Finally, call the send_goal method with a value:

1
2
3
4
5
6
def main(args=None):
    rclpy.init(args=args)

    action_client = FibonacciActionClient()

    action_client.send_goal(10)

Let’s test our action client by first running an action server built in the tutorial on Writing an Action Server (Python):

# Linux/OSX
python3 fibonacci_action_server.py
# Windows
python fibonacci_action_server.py

In another terminal, run the action client:

# Linux/OSX
python3 fibonacci_action_client.py
# Windows
python fibonacci_action_client.py

Tada! You should see messages printed by the action server as it successfully executes the goal.

Getting Feedback

Our action client can send goals. Nice! But it would be great if we could get some feedback about the goals we send from the action server. Easy, let’s write a callback function for feedback messages:

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
14
15
16
17
class FibonacciActionClient(Node):

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

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

        self._action_client.wait_for_server()

        self._action_client.send_goal_async(goal_msg)

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

In the callback we get the feedback portion of the message and print the partial_sequence field to the screen.

We need to register the callback with the action client. This is achieved by passing the callback to the action client when we send a goal:

1
2
3
4
5
6
7
8
    def send_goal(self, order):
        goal_msg = Fibonacci.Goal()
        goal_msg.order = order

        self._action_client.wait_for_server()

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

You’ll notice at this point that our action client is not printing any feedback. This is because we’re missing a call to rclpy.spin() in order to process callbacks on our node. Let’s add it:

1
2
3
4
5
6
7
8
def main(args=None):
    rclpy.init(args=args)

    action_client = FibonacciActionClient()

    action_client.send_goal(10)

    rclpy.spin(action_client)

We’re all set. If we run our action client, you should see feedback being printed to the screen.

Getting a Result

So we can send a goal, but how do we know when it is completed? We can get the result information with a couple steps. First, we need to get a goal handle for the goal we sent. Then, we can use the goal handle to request the result.

The ActionClient.send_goal_async() method returns a future to a goal handle. Let’s register a callback for when the future is complete:

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
14
15
16
17
18
19
20
class FibonacciActionClient(Node):

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

    def send_goal(self, order):
        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()

Note, the future is completed when an action server accepts or rejects the goal request. We can actually check to see if the goal was rejected and return early since we know there will be no result:

1
2
3
4
5
6
7
8
    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 :)')

Now that we’ve got a goal handle, we can use it to request the result with the method get_result_async(). Similar to sending the goal, we will get a future that will complete when the result is ready. Let’s register a callback just like we did for the goal response:

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
14
15
16
17
    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))
        rclpy.shutdown()

In the callback, we log the result sequence and shutdown ROS for a clean exit.

With an action server running in a separate terminal, go ahead and try running our Fibonacci action client!

# Linux/OSX
python3 fibonacci_action_client.py
# Windows
python fibonacci_action_client.py

You should see logged messages for the goal being accepted, feedback, and the final result.