Skip to main content
🎯 ActionsROS 2 · June 2026

ROS 2 Actions Guide 2026

Master ROS 2 actions for long-running tasks: define .action files, build Python action servers with goal/feedback/result/cancel, create async action clients with send_goal_async, and debug with the ros2 action CLI.

When to Use Actions

Nav2's NavigateToPose is an action — sending the robot to a goal takes seconds or minutes, provides distance feedback during navigation, and can be cancelled if the goal changes. Use actions whenever the operation: (1) takes longer than ~100ms, (2) provides meaningful intermediate progress, or (3) needs to be interrupted mid-execution.

1

Actions vs Services vs Topics

Actions are the right tool when an operation takes time, provides incremental feedback, and needs to be cancellable. Choose the right communication pattern for each task.

text
ROS 2 Communication Patterns
═══════════════════════════════════════════════════════
Topic (pub/sub)
  • One-to-many, fire-and-forget
  • No acknowledgment, no guarantee of delivery
  • Use for: sensor streams, state broadcasts, periodic data
  • ros2 topic pub / echo

Service (request/response)
  • One client, one server — synchronous
  • Client blocks (or uses call_async) until result arrives
  • Use for: quick configuration, status queries, one-shot commands
  • Duration: <100ms ideal; use action for anything longer
  • ros2 service call

Action (goal/feedback/result)
  • Long-running tasks with progress reporting and cancellation
  • Client sends GOAL → server accepts/rejects → sends FEEDBACK → sends RESULT
  • Non-blocking: client continues while goal executes in background
  • Use for: navigate to pose, execute trajectory, pick object
  • ros2 action send_goal

Action States:
  CLIENT sends goal → SERVER: ACCEPTED | REJECTED
  If ACCEPTED → executing → FEEDBACK (periodic) → RESULT
  Client can send CANCEL at any time
  Server can ABORT (unexpected failure) or SUCCEED
2

Action Definition (.action File)

An .action file has three sections separated by ---: Goal (what the client requests), Result (what the server returns on completion), Feedback (incremental progress updates).

yaml
# action/Navigate.action
# ── Goal (sent by client) ─────────────────────────────────
float64 target_x
float64 target_y
float64 target_yaw
float64 tolerance      # acceptable distance from goal

---

# ── Result (sent by server when done) ─────────────────────
bool success
float64 final_x
float64 final_y
string message

---

# ── Feedback (sent periodically while executing) ───────────
float64 current_x
float64 current_y
float64 distance_remaining
float64 estimated_seconds_remaining

# Register in CMakeLists.txt:
# rosidl_generate_interfaces(${PROJECT_NAME}
#   "action/Navigate.action"
#   DEPENDENCIES geometry_msgs std_msgs
# )

# Usage after build:
# from my_pkg.action import Navigate
# from my_pkg.action._navigate import Navigate_Goal
# from my_pkg.action._navigate import Navigate_Result
# from my_pkg.action._navigate import Navigate_Feedback

Convention: Goal fields are what the client specifies, Feedback is progress toward the goal, Result is the final outcome. Keep Feedback lightweight — it may publish at 10-50 Hz.

3

Python Action Server

The action server accepts goals, executes them (usually in a separate thread), publishes feedback, and returns a result. Use rclpy's ActionServer class.

python
import rclpy
from rclpy.node import Node
from rclpy.action import ActionServer, CancelResponse, GoalResponse
from rclpy.action.server import ServerGoalHandle
from my_pkg.action import Navigate
import time
import math


class NavigateActionServer(Node):
    def __init__(self):
        super().__init__("navigate_action_server")

        self._server = ActionServer(
            self,
            Navigate,
            "navigate",
            execute_callback=self._execute_cb,
            goal_callback=self._goal_cb,
            cancel_callback=self._cancel_cb,
        )
        self._current_x = 0.0
        self._current_y = 0.0

    def _goal_cb(self, goal_request) -> GoalResponse:
        """Called when client sends a new goal. Accept or reject."""
        self.get_logger().info(
            f"Received goal: ({goal_request.target_x:.1f}, {goal_request.target_y:.1f})"
        )
        # Could reject if another goal is running
        return GoalResponse.ACCEPT

    def _cancel_cb(self, goal_handle) -> CancelResponse:
        """Called when client requests cancellation."""
        self.get_logger().info("Cancellation requested")
        return CancelResponse.ACCEPT   # or CancelResponse.REJECT

    def _execute_cb(self, goal_handle: ServerGoalHandle):
        """Main execution callback — runs in separate thread."""
        goal = goal_handle.request
        feedback = Navigate.Feedback()

        self.get_logger().info("Executing goal...")

        while True:
            # Check if cancellation was requested
            if goal_handle.is_cancel_requested:
                goal_handle.canceled()
                result = Navigate.Result()
                result.success = False
                result.message = "Cancelled by client"
                return result

            # Simulate movement toward goal
            dx = goal.target_x - self._current_x
            dy = goal.target_y - self._current_y
            dist = math.sqrt(dx**2 + dy**2)

            if dist < goal.tolerance:
                break   # reached goal

            # Move a step
            step = min(0.1, dist)
            self._current_x += step * dx / dist
            self._current_y += step * dy / dist

            # Publish feedback
            feedback.current_x = self._current_x
            feedback.current_y = self._current_y
            feedback.distance_remaining = dist - step
            goal_handle.publish_feedback(feedback)

            time.sleep(0.1)   # simulate 10 Hz control loop

        # Goal completed successfully
        goal_handle.succeed()
        result = Navigate.Result()
        result.success = True
        result.final_x = self._current_x
        result.final_y = self._current_y
        result.message = "Goal reached"
        return result


def main():
    rclpy.init()
    node = NavigateActionServer()
    rclpy.spin(node)

The execute_callback runs in a dedicated thread by default. This means you can safely use time.sleep() without blocking the executor. If you need multiple concurrent goals, set callback_group and use MultiThreadedExecutor.

4

Python Action Client

The action client sends goals asynchronously, receives feedback callbacks during execution, and gets the result when the server finishes.

python
import rclpy
from rclpy.node import Node
from rclpy.action import ActionClient
from my_pkg.action import Navigate


class NavigateClient(Node):
    def __init__(self):
        super().__init__("navigate_client")
        self._client = ActionClient(self, Navigate, "navigate")

    def send_goal(self, x: float, y: float):
        """Send goal and return result (blocking via spin_until_future_complete)."""
        self._client.wait_for_server()

        goal = Navigate.Goal()
        goal.target_x = x
        goal.target_y = y
        goal.tolerance = 0.1

        self.get_logger().info(f"Sending goal: ({x}, {y})")

        # send_goal_async returns a Future<ClientGoalHandle>
        send_goal_future = self._client.send_goal_async(
            goal,
            feedback_callback=self._feedback_cb
        )

        rclpy.spin_until_future_complete(self, send_goal_future)
        goal_handle = send_goal_future.result()

        if not goal_handle.accepted:
            self.get_logger().error("Goal rejected!")
            return None

        self.get_logger().info("Goal accepted")

        # Wait for result
        get_result_future = goal_handle.get_result_async()
        rclpy.spin_until_future_complete(self, get_result_future)

        result = get_result_future.result().result
        status = get_result_future.result().status

        self.get_logger().info(
            f"Result: success={result.success}, msg={result.message}"
        )
        return result

    def _feedback_cb(self, feedback_msg):
        fb = feedback_msg.feedback
        self.get_logger().info(
            f"Feedback: dist_remaining={fb.distance_remaining:.2f}"
        )

    def cancel_goal(self, goal_handle):
        """Cancel the active goal."""
        cancel_future = goal_handle.cancel_goal_async()
        rclpy.spin_until_future_complete(self, cancel_future)


def main():
    rclpy.init()
    client = NavigateClient()
    result = client.send_goal(5.0, 3.0)
    client.destroy_node()
    rclpy.shutdown()
5

Cancellation Pattern

Cancellation is triggered from the client but must be cooperatively handled by the server. The server checks is_cancel_requested in its execution loop.

python
import rclpy
from rclpy.action import ActionClient
from my_pkg.action import Navigate
import threading


class NavigateWithCancelClient(rclpy.node.Node):
    def __init__(self):
        super().__init__("nav_cancel_client")
        self._client = ActionClient(self, Navigate, "navigate")
        self._goal_handle = None
        self._lock = threading.Lock()

    def send_goal(self, x, y):
        self._client.wait_for_server()
        goal = Navigate.Goal()
        goal.target_x = x
        goal.target_y = y
        goal.tolerance = 0.1

        future = self._client.send_goal_async(goal)
        future.add_done_callback(self._goal_response_cb)

    def _goal_response_cb(self, future):
        handle = future.result()
        if not handle.accepted:
            self.get_logger().warn("Goal rejected")
            return
        with self._lock:
            self._goal_handle = handle
        self.get_logger().info("Goal accepted — running")
        handle.get_result_async().add_done_callback(self._result_cb)

    def _result_cb(self, future):
        result = future.result().result
        self.get_logger().info(f"Done: {result.message}")

    def cancel(self):
        """Call from anywhere to cancel the active goal."""
        with self._lock:
            handle = self._goal_handle
        if handle:
            self.get_logger().info("Sending cancel")
            handle.cancel_goal_async()
        else:
            self.get_logger().warn("No active goal to cancel")

The server's cancel_callback decides whether to ACCEPT or REJECT the cancellation. Always return CancelResponse.ACCEPT unless you have a reason (e.g. goal is past the point of no return). After accept, check is_cancel_requested in your execute loop.

6

Action CLI Tools

ros2 action commands let you inspect and manually trigger actions from the terminal — useful for debugging without writing client code.

bash
# List all available action servers
ros2 action list

# Show action type and details
ros2 action info /navigate
# → Action: /navigate
# → Action type: my_pkg/action/Navigate
# → Action clients: 0
# → Action servers: 1

# Show the .action interface definition
ros2 interface show my_pkg/action/Navigate

# ── Send a goal from the CLI ────────────────────────────
# ros2 action send_goal <action_name> <type> <goal_yaml>
ros2 action send_goal /navigate my_pkg/action/Navigate   "{target_x: 3.0, target_y: 2.0, target_yaw: 0.0, tolerance: 0.1}"

# Send goal and wait for feedback (add -f flag)
ros2 action send_goal -f /navigate my_pkg/action/Navigate   "{target_x: 3.0, target_y: 2.0, target_yaw: 0.0, tolerance: 0.1}"

# Example output:
# Sending goal:
#    target_x: 3.0
#    target_y: 2.0
# Goal accepted with ID: 4a7b...
# Feedback:
#    distance_remaining: 2.45
# Feedback:
#    distance_remaining: 1.23
# Result:
#    success: True
#    message: Goal reached

Quick Reference

ConceptDetails
Use action whenOperation >100ms, needs progress updates, or should be cancellable
.action file sectionsGoal --- Result --- Feedback (three sections separated by ---)
Python serverActionServer(node, Type, name, execute_callback=fn)
Server successgoal_handle.succeed(); return Result(...)
Server cancel checkif goal_handle.is_cancel_requested: goal_handle.canceled(); return
Python clientActionClient(node, Type, name).send_goal_async(goal, feedback_callback=fn)
Client wait for resultrclpy.spin_until_future_complete(node, get_result_future)
Cancel from clientgoal_handle.cancel_goal_async()
CLI listros2 action list / ros2 action info /name
CLI send goalros2 action send_goal -f /name type/Action "{yaml}"