When working with robots, not every task is instantaneous. Some operations take time: navigating across a room, picking up an object, scanning an area, or performing a long computation.
In ROS 2, these “long-running” tasks need a special way for nodes to talk to each other — one that allows progress updates and the ability to stop the task if needed.
This is where ROS 2 Actions come in.
In this article, we’ll explore what Actions are, why they’re different from Topics and Services, and then we’ll create a fully functional Action Server in Python that calculates the Fibonacci sequence. This example will serve as a starting point for more advanced action-based tasks you might want to implement in your robotics projects.
In ROS 2, nodes communicate using three main patterns: Topics, Services, and Actions.
Communication Type | Best For | Pattern |
---|---|---|
Topic | Continuous data streams (e.g., sensor readings, camera feeds) | Publish / Subscribe |
Service | Instant request–response (e.g., converting coordinates) | Request / Reply |
Action | Long-running tasks (e.g., navigation, manipulation) | Goal → Feedback → Result (with Cancel option) |
Services are perfect for quick tasks. You send a request, wait for the reply, and you’re done. But if the task takes 5, 10, or 30 seconds, the client is left waiting with no idea what’s happening — and no way to stop it mid-execution.
Actions solve this problem by introducing:
Feedback messages — progress updates sent while the task is running.
Cancel messages — the ability to stop a task before it completes.
Here’s how Actions work in ROS 2:
Goal — The client sends the task parameters.
Example: “Move to coordinates (x: 1.2, y: 0.5)” or “Calculate Fibonacci sequence up to order 10.”
Feedback — While the server works, it sends updates to the client.
Example: “I’ve reached 50% of the path” or “Current Fibonacci sequence: 0, 1, 1, 2, 3…”
Result — When the task finishes, the server sends the final outcome.
Example: “Arrived at destination” or “Final Fibonacci sequence: 0, 1, 1, 2, 3, 5, 8…”
Cancel (optional) — At any time, the client can stop the task.
Example: “Stop moving, the target object disappeared.”
Imagine you have:
A vision node that detects the position of a pen.
A manipulation node that can move the robot’s arm to grab objects.
You could design the manipulation node as an Action Server:
When the pen is detected, the vision node sends a goal to the manipulation node: “Grab the pen at position (x, y, z).”
The manipulation node starts moving the arm and sends feedback like “Arm halfway to position” or “Gripper opening.”
If the pen falls off the table, the vision node can send a cancel request, and the server stops the movement.
Regardless of whether it completes or is canceled, the server sends a result back.
This flexibility is what makes Actions essential for robotics.
For our first practical Action example, we’ll implement a Python Action Server that calculates the Fibonacci sequence up to a user-defined order.
The Fibonacci sequence is a series where each number is the sum of the two preceding ones, starting from 0 and 1.
It’s simple to understand.
It allows us to focus on the Action Server logic instead of robot hardware.
It gives us a natural way to send progress updates (feedback) after each number is calculated.
We’ll create our Action Server in the arduinobot_py_examples
package.
In ROS 2, an action is defined in an .action
file inside an action
folder of a package. Let’s define ours in the arduinobot_msgs
package.
File: arduinobot_msgs/action/Fibonacci.action
# Goal
int32 order
---
# Result
int32[] sequence
---
# Feedback
int32[] partial_sequence
Goal: One integer (order
) — the length of the sequence to compute.
Result: The full Fibonacci sequence.
Feedback: The sequence so far.
CMakeLists.txt
and package.xml
Add the new action file to rosidl_generate_interfaces
in CMakeLists.txt
:
rosidl_generate_interfaces(${PROJECT_NAME}
"srv/AddTwoInts.srv"
"action/Fibonacci.action"
)
And in package.xml
add:
action_msgs
Then rebuild the workspace:
cd ~/arduinobot_ws
colcon build
File: arduinobot_py_examples/simple_action_server.py
import rclpy
from rclpy.node import Node
from rclpy.action import ActionServer
from arduinobot_msgs.action import Fibonacci
import time
class SimpleActionServer(Node):
def __init__(self):
super().__init__("simple_action_server")
self.action_server = ActionServer(
self,
Fibonacci,
"fibonacci",
self.goal_callback
)
self.get_logger().info("Fibonacci Action Server started!")
def goal_callback(self, goal_handle):
self.get_logger().info(
f"Received goal request: order = {goal_handle.request.order}"
)
feedback_msg = Fibonacci.Feedback()
feedback_msg.partial_sequence = [0, 1]
for i in range(1, goal_handle.request.order):
feedback_msg.partial_sequence.append(
feedback_msg.partial_sequence[i] + feedback_msg.partial_sequence[i - 1]
)
self.get_logger().info(f"Feedback: {feedback_msg.partial_sequence}")
goal_handle.publish_feedback(feedback_msg)
time.sleep(1)
goal_handle.succeed()
result = Fibonacci.Result()
result.sequence = feedback_msg.partial_sequence
return result
def main():
rclpy.init()
action_server = SimpleActionServer()
rclpy.spin(action_server)
rclpy.shutdown()
if __name__ == "__main__":
main()
We’ll dissect simple_action_server.py
top to bottom so you know exactly what every line does.
import rclpy
from rclpy.node import Node
from rclpy.action import ActionServer
from arduinobot_msgs.action import Fibonacci
import time
rclpy
, Node
: ROS 2 Python client and base node class.
ActionServer
: helper that wires up the Action’s Goal/Feedback/Result plumbing.
Fibonacci
: the custom .action
type you defined (Goal
, Feedback
, Result
).
time
: we’ll sleep(1)
to simulate a long-running job and emit multiple feedbacks.
class SimpleActionServer(Node):
def __init__(self):
super().__init__("simple_action_server")
We create a ROS 2 node named simple_action_server
. You’ll see this name in ros2 node list
and in logs.
self.action_server = ActionServer(
self, # the hosting node
Fibonacci, # the Action interface (Goal/Feedback/Result schemas)
"fibonacci", # the action name (ROS graph resource)
self.goal_callback # function that executes each accepted goal
)
self.get_logger().info("Fibonacci Action Server started!")
The type (Fibonacci
) tells ROS how to serialize messages.
The name (/fibonacci
) is how clients discover and call your server.
The callback is invoked per-goal; it performs the work, streams feedback, and returns a result.
Tip: In rclpy docs this parameter is often called
execute_callback
. We’re calling itgoal_callback
to stick with the lesson’s naming, but it’s the function that runs the goal.
def goal_callback(self, goal_handle):
self.get_logger().info(
f"Received goal request: order = {goal_handle.request.order}"
)
goal_handle
gives you access to the incoming goal request (here, order
) and tools to publish feedback, set status, etc.
feedback_msg = Fibonacci.Feedback()
feedback_msg.partial_sequence = [0, 1]
The Action’s Feedback type carries partial progress.
We seed the Fibonacci sequence with [0, 1]
, so each loop iteration can append the next term.
Note: If you want mathematically strict behavior for tiny orders (e.g.,
order=0
ororder=1
), you can clamp or slice the list before returning the result. This sample keeps it simple.
for i in range(1, goal_handle.request.order):
feedback_msg.partial_sequence.append(
feedback_msg.partial_sequence[i] +
feedback_msg.partial_sequence[i - 1]
)
self.get_logger().info(f"Feedback: {feedback_msg.partial_sequence}")
goal_handle.publish_feedback(feedback_msg)
time.sleep(1) # simulate processing time
Each iteration computes the next Fibonacci number and appends it.
We log and publish the current partial sequence as feedback to the client.
sleep(1)
just simulates work so you can actually see multiple feedback updates.
In real robots, this “work” would be path planning, motion, or perception—no
sleep
, just real computation.
goal_handle.succeed()
result = Fibonacci.Result()
result.sequence = feedback_msg.partial_sequence
return result
succeed()
sets the goal status to SUCCEEDED.
We fill the Result with the full sequence and return it—ROS 2 sends it back to the client.
Optional enhancement: handle cancellations. Inside the loop, check:
if goal_handle.is_cancel_requested:
goal_handle.canceled()
result = Fibonacci.Result()
result.sequence = feedback_msg.partial_sequence
return result
That lets clients abort long tasks cleanly.
def main():
rclpy.init()
action_server = SimpleActionServer()
rclpy.spin(action_server)
rclpy.shutdown()
rclpy.init()
brings ROS 2 online for this process.
rclpy.spin()
keeps the node alive to accept goals and publish feedback.
On Ctrl-C, we cleanly shutdown()
.
In arduinobot_py_examples/setup.py
:
'console_scripts': [
'simple_action_server = arduinobot_py_examples.simple_action_server:main',
]
Rebuild:
colcon build
. install/setup.bash
ros2 run arduinobot_py_examples simple_action_server
ros2 action list
ros2 action send_goal /fibonacci arduinobot_msgs/action/Fibonacci "order: 10" -f
You’ll see feedback messages in real-time and, at the end, the full sequence.