In the previous article, we implemented a ROS 2 Action Server in Python that calculates the Fibonacci sequence. We also saw how to interact with it using the ROS 2 CLI (ros2 action send_goal
).
Now, we’ll take a step further and implement a ROS 2 Action Client in Python.
This client node will connect directly to our Fibonacci Action Server, send a goal request, handle feedback messages in real time, and finally display the result when the computation is complete.
If you are following along in C++, you can skip ahead to the next article, where we will replicate the same action client in C++.
As we’ve already seen, ROS 2 Actions are designed for long-running tasks where:
A goal is sent by the client (e.g., “compute Fibonacci sequence up to order 10”).
The server works on that request, sending periodic feedback (e.g., partial sequence).
When complete, the server returns a result message.
This makes actions perfect for robotics tasks like navigation, arm manipulation, or—in our simplified case—computing the Fibonacci sequence.
We’ll place our client inside the same package as before, arduinobot_py_examples
, under a new script:
arduinobot_py_examples/arduinobot_py_examples/simple_action_client.py
Here’s the complete code for the client:
import rclpy
from rclpy.node import Node
from rclpy.action import ActionClient
from arduinobot_msgs.action import Fibonacci
class SimpleActionClient(Node):
def __init__(self):
super().__init__("simple_action_client")
# Create action client to connect to the 'fibonacci' action server
self.action_client = ActionClient(self, Fibonacci, "fibonacci")
# Wait until the server becomes available
self.action_client.wait_for_server()
# Create a goal message
goal = Fibonacci.Goal()
goal.order = 10
# Send the goal asynchronously, register callbacks
self.future = self.action_client.send_goal_async(
goal, feedback_callback=self.feedbackCallback
)
self.future.add_done_callback(self.responseCallback)
def responseCallback(self, future):
goal_handle = future.result()
if not goal_handle.accepted:
self.get_logger().info("Goal rejected :(")
return
self.get_logger().info("Goal accepted :)")
# Wait for the result asynchronously
result_future = goal_handle.get_result_async()
result_future.add_done_callback(self.resultCallback)
def feedbackCallback(self, feedback_msg):
self.get_logger().info(
f"Received feedback: {feedback_msg.feedback.partial_sequence}"
)
def resultCallback(self, future):
result = future.result().result
self.get_logger().info(f"Result: {result.sequence}")
rclpy.shutdown()
def main():
rclpy.init()
action_client = SimpleActionClient()
rclpy.spin(action_client)
if __name__ == "__main__":
main()
Let’s go line by line and understand what’s happening.
import rclpy
from rclpy.node import Node
from rclpy.action import ActionClient
from arduinobot_msgs.action import Fibonacci
rclpy
: ROS 2 Python client library.
Node
: Base class for any ROS 2 node.
ActionClient
: Class to create and manage clients for action servers.
Fibonacci
: Our custom action definition (.action
file).
class SimpleActionClient(Node):
def __init__(self):
super().__init__("simple_action_client")
Defines a new node named "simple_action_client"
.
All ROS 2 interactions (logging, publishers, subscribers, actions) happen inside a node.
self.action_client = ActionClient(self, Fibonacci, "fibonacci")
Connects this client to an action server named "fibonacci"
.
Uses the Fibonacci
action interface.
If the server isn’t running, this will wait until it becomes available.
goal = Fibonacci.Goal()
goal.order = 10
Creates a goal message asking for Fibonacci sequence of order 10
.
self.future = self.action_client.send_goal_async(
goal, feedback_callback=self.feedbackCallback
)
self.future.add_done_callback(self.responseCallback)
send_goal_async
sends the request.
We also pass a feedback callback, executed whenever the server sends progress updates.
The returned future
will tell us if the goal was accepted or rejected.
def responseCallback(self, future):
goal_handle = future.result()
if not goal_handle.accepted:
self.get_logger().info("Goal rejected :(")
return
self.get_logger().info("Goal accepted :)")
The server may reject the request (e.g., invalid order).
Otherwise, we get a goal_handle
, which lets us request the final result.
def feedbackCallback(self, feedback_msg):
self.get_logger().info(
f"Received feedback: {feedback_msg.feedback.partial_sequence}"
)
Triggered multiple times during execution.
Prints the partial Fibonacci sequence as it grows.
def resultCallback(self, future):
result = future.result().result
self.get_logger().info(f"Result: {result.sequence}")
rclpy.shutdown()
Once the server completes, this callback fires.
Prints the final sequence.
Shuts down the node since we’re done.
def main():
rclpy.init()
action_client = SimpleActionClient()
rclpy.spin(action_client)
Initializes ROS 2.
Creates the action client node.
Spins until the client shuts down.
Rebuild your workspace:
cd ~/arduinobot_ws
colcon build
Source it:
. install/setup.bash
ros2 run arduinobot_py_examples simple_action_server
ros2 run arduinobot_py_examples simple_action_client
We now have a working Python Action Client that:
Connects to the Fibonacci Action Server.
Sends a goal request.
Receives live feedback.
Prints the final result.
This is a foundation for more complex robotics tasks where you need long-running interactions between clients and servers.