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 C++ 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.
In this hands-on section, we’ll create a C++ Action Server that calculates the Fibonacci sequence. The order of the sequence will be sent as the Goal, and the server will return the full sequence as the Result, sending intermediate numbers as Feedback.
#include
#include
#include
#include
#include
#include "arduinobot_msgs/action/fibonacci.hpp"
namespace arduinobot_cpp_examples
{
class SimpleActionServer : public rclcpp::Node
{
public:
using Fibonacci = arduinobot_msgs::action::Fibonacci;
using GoalHandleFibonacci = rclcpp_action::ServerGoalHandle;
explicit SimpleActionServer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions())
: Node("simple_action_server", options)
{
using namespace std::placeholders;
action_server_ = rclcpp_action::create_server(
this,
"fibonacci",
std::bind(&SimpleActionServer::goalCallback, this, _1, _2),
std::bind(&SimpleActionServer::cancelCallback, this, _1),
std::bind(&SimpleActionServer::acceptedCallback, this, _1)
);
RCLCPP_INFO(get_logger(), "Starting the Action Server");
}
private:
rclcpp_action::Server::SharedPtr action_server_;
rclcpp_action::GoalResponse goalCallback(
const rclcpp_action::GoalUUID & uuid,
std::shared_ptr goal)
{
RCLCPP_INFO(get_logger(), "Received goal request with order %d", goal->order);
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
}
rclcpp_action::CancelResponse cancelCallback(
const std::shared_ptr goal_handle)
{
RCLCPP_INFO(get_logger(), "Received request to cancel goal");
return rclcpp_action::CancelResponse::ACCEPT;
}
void acceptedCallback(const std::shared_ptr goal_handle)
{
std::thread{std::bind(&SimpleActionServer::execute, this, goal_handle)}.detach();
}
void execute(const std::shared_ptr goal_handle)
{
RCLCPP_INFO(get_logger(), "Executing goal");
rclcpp::Rate loop_rate(1);
const auto goal = goal_handle->get_goal();
auto feedback = std::make_shared();
auto & sequence = feedback->partial_sequence;
sequence.push_back(0);
sequence.push_back(1);
auto result = std::make_shared();
for (int i = 1; (i < goal->order) && rclcpp::ok(); ++i)
{
if (goal_handle->is_canceling())
{
result->sequence = sequence;
goal_handle->canceled(result);
RCLCPP_INFO(get_logger(), "Goal canceled");
return;
}
sequence.push_back(sequence[i] + sequence[i - 1]);
goal_handle->publish_feedback(feedback);
RCLCPP_INFO(get_logger(), "Publish feedback");
loop_rate.sleep();
}
if (rclcpp::ok())
{
result->sequence = sequence;
goal_handle->succeed(result);
RCLCPP_INFO(get_logger(), "Goal succeeded");
}
}
};
} // namespace arduinobot_cpp_examples
#include
RCLCPP_COMPONENTS_REGISTER_NODE(arduinobot_cpp_examples::SimpleActionServer)
We’ll dissect simple_action_server.cpp
from top to bottom. Each snippet is the exact line(s) you need, followed by why they matter and how they fit together.
#include
#include
#include
#include
#include
#include "arduinobot_msgs/action/fibonacci.hpp"
Standard headers:
<memory>
for smart pointers,
<thread>
to run execution asynchronously,
<vector>
for the sequence.
ROS 2:
rclcpp
core node API,
rclcpp_action
Action server utilities.
Your custom interface: Fibonacci
(defines Goal, Feedback, Result).
namespace arduinobot_cpp_examples
{
class SimpleActionServer : public rclcpp::Node
{
public:
using Fibonacci = arduinobot_msgs::action::Fibonacci;
using GoalHandleFibonacci = rclcpp_action::ServerGoalHandle;
Namespacing keeps symbols clean.
Type aliases:
Fibonacci
→ shorter access to the action type.
GoalHandleFibonacci
→ the goal handle used everywhere (status, feedback, result).
explicit SimpleActionServer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions())
: Node("simple_action_server", options)
{
using namespace std::placeholders;
action_server_ = rclcpp_action::create_server(
this, // hosting node
"fibonacci", // action name in the graph
std::bind(&SimpleActionServer::goalCallback, this, _1, _2),
std::bind(&SimpleActionServer::cancelCallback, this, _1),
std::bind(&SimpleActionServer::acceptedCallback,this, _1)
);
RCLCPP_INFO(get_logger(), "Starting the Action Server");
}
Node name: visible in ros2 node list
and logs.
create_server
signature (for reference):node, action_name, goal_cb(uuid, goal), cancel_cb(goal_handle), accepted_cb(goal_handle)
std::bind
+ placeholders connect member functions to the server’s callback signatures.
private:
rclcpp_action::Server::SharedPtr action_server_;
Keeps the server alive as long as the node exists.
Shared pointer (lifecycle owned by your node).
rclcpp_action::GoalResponse goalCallback(
const rclcpp_action::GoalUUID & uuid,
std::shared_ptr goal)
{
(void)uuid; // not used here, but available if you need per-goal logic
RCLCPP_INFO(get_logger(), "Received goal request with order %d", goal->order);
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
}
Called whenever a client sends a Goal.
You could validate the request here (e.g., reject negative orders):
if (goal->order < 1) return rclcpp_action::GoalResponse::REJECT;
rclcpp_action::CancelResponse cancelCallback(
const std::shared_ptr /*goal_handle*/)
{
RCLCPP_INFO(get_logger(), "Received request to cancel goal");
return rclcpp_action::CancelResponse::ACCEPT;
}
Allows clients to stop long tasks gracefully.
Returning ACCEPT
doesn’t cancel instantly — the execute loop must check and honor cancellation.
void acceptedCallback(const std::shared_ptr goal_handle)
{
std::thread{std::bind(&SimpleActionServer::execute, this, goal_handle)}.detach();
}
The accepted callback fires after a goal is accepted.
We launch execute()
on a separate thread so the node remains responsive (spinning, handling more goals).
detach()
→ fire-and-forget; ROS 2 executor isn’t blocked.
Alternative: use a dedicated executor, a thread pool, or
std::async
if you want structured joining. For this tutorial,detach()
is perfect.
void execute(const std::shared_ptr goal_handle)
{
RCLCPP_INFO(get_logger(), "Executing goal");
rclcpp::Rate loop_rate(1); // 1 Hz
const auto goal = goal_handle->get_goal();
auto feedback = std::make_shared();
auto & sequence = feedback->partial_sequence;
sequence.push_back(0);
sequence.push_back(1);
auto result = std::make_shared();
for (int i = 1; (i < goal->order) && rclcpp::ok(); ++i)
{
// 8.1 honor cancellations
if (goal_handle->is_canceling())
{
result->sequence = sequence; // partial result
goal_handle->canceled(result); // set final state + send result
RCLCPP_INFO(get_logger(), "Goal canceled");
return;
}
// 8.2 compute next Fibonacci term
sequence.push_back(sequence[i] + sequence[i - 1]);
// 8.3 send feedback
goal_handle->publish_feedback(feedback);
RCLCPP_INFO(get_logger(), "Publish feedback");
// 8.4 throttle loop so feedback is visible
loop_rate.sleep();
}
// 8.5 success path
if (rclcpp::ok())
{
result->sequence = sequence;
goal_handle->succeed(result); // set final state + send result
RCLCPP_INFO(get_logger(), "Goal succeeded");
}
}
What’s happening:
loop_rate(1)
→ one iteration per second (so you see feedback).
We keep a single feedback message and mutate its vector; this is efficient and normal in ROS 2.
Cancellation is checked every iteration — if requested, we send the partial result and exit.
On success, we fill the Result and mark the goal SUCCEEDED.
Edge cases (optional hardening):
order <= 1
: you might want to short-circuit and return[0]
or[0,1]
as appropriate.Large orders: Fibonacci grows fast; consider
int64_t
and bounds checking.
ros2 run
it)
#include
RCLCPP_COMPONENTS_REGISTER_NODE(arduinobot_cpp_examples::SimpleActionServer)
Registers this class as a component; your CMake uses rclcpp_components_register_node
to build an executable for you.
This is why you can simply do:
ros2 run arduinobot_cpp_examples simple_action_server
. install/setup.bash
ros2 run arduinobot_cpp_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.