Skip to main content

Documentation Index

Fetch the complete documentation index at: https://mintlify.com/PX4/PX4-Autopilot/llms.txt

Use this file to discover all available pages before exploring further.

Offboard control lets your ROS 2 node send setpoints directly to PX4, bypassing the onboard flight modes. PX4 follows the setpoints your node publishes as long as the node keeps sending a heartbeat at a sufficient rate. If the heartbeat stops, PX4 falls back to a failsafe behavior. This pattern is the foundation for autonomous missions, computer vision guided flight, and any application that needs programmatic control of the vehicle.
Offboard control is inherently dangerous. Always have a way to regain manual control — either via RC override or a ground station — before testing on a real vehicle.

Required topics

Three topics form the core of the offboard control pattern:
TopicDirectionPurpose
OffboardControlModeROS 2 → PX4 (/fmu/in/)Declares which control dimension is active (position, velocity, attitude, etc.) and serves as the heartbeat
TrajectorySetpointROS 2 → PX4 (/fmu/in/)Carries the actual position or velocity target in NED frame
VehicleCommandROS 2 → PX4 (/fmu/in/)Sends MAVLink-style commands to arm the vehicle and switch flight modes
PX4 uses the NED (North-East-Down) coordinate frame. The Z axis points down, so a positive altitude of 5 metres is expressed as z = -5.0. If your nodes use the ROS standard ENU frame, convert before publishing.

The offboard control loop

PX4 requires a continuous stream of OffboardControlMode messages before it will arm in offboard mode and to stay in offboard mode once flying. If the stream drops below approximately 2 Hz, PX4 exits offboard mode automatically. The correct sequence is:
1

Start publishing OffboardControlMode and TrajectorySetpoint

Begin streaming both messages at 10 Hz before attempting to switch modes or arm. PX4 will not accept the mode switch until it has received several messages.
2

Switch to offboard mode

Send a VehicleCommand with VEHICLE_CMD_DO_SET_MODE (command 176), param1 = 1 (base mode: custom), param2 = 6 (custom main mode: offboard).
3

Arm the vehicle

Send a VehicleCommand with VEHICLE_CMD_COMPONENT_ARM_DISARM (command 400), param1 = 1.0 to arm.
4

Continue streaming setpoints

Keep publishing OffboardControlMode and TrajectorySetpoint on every timer tick. This is both the heartbeat and the setpoint delivery mechanism.

Example node structure (Python)

The following example shows a minimal ROS 2 Python node that arms a multicopter and commands it to hover at 5 metres.
import rclpy
from rclpy.node import Node
from rclpy.qos import QoSProfile, ReliabilityPolicy, HistoryPolicy, DurabilityPolicy

from px4_msgs.msg import OffboardControlMode, TrajectorySetpoint, VehicleCommand


class OffboardControlNode(Node):
    def __init__(self) -> None:
        super().__init__('offboard_control')

        qos = QoSProfile(
            reliability=ReliabilityPolicy.BEST_EFFORT,
            durability=DurabilityPolicy.TRANSIENT_LOCAL,
            history=HistoryPolicy.KEEP_LAST,
            depth=1,
        )

        self.offboard_mode_pub = self.create_publisher(
            OffboardControlMode, '/fmu/in/OffboardControlMode', qos)
        self.trajectory_pub = self.create_publisher(
            TrajectorySetpoint, '/fmu/in/TrajectorySetpoint', qos)
        self.command_pub = self.create_publisher(
            VehicleCommand, '/fmu/in/VehicleCommand', qos)

        self._counter = 0
        # 10 Hz timer — publishes heartbeat and setpoints on every tick
        self.timer = self.create_timer(0.1, self._timer_callback)

    def _timer_callback(self) -> None:
        # Publish OffboardControlMode at 10 Hz (heartbeat + control type)
        self._publish_offboard_control_mode()

        # Publish TrajectorySetpoint at 10 Hz
        self._publish_trajectory_setpoint()

        if self._counter == 10:
            # Switch to offboard mode after 10 initial setpoints
            self._send_vehicle_command(
                VehicleCommand.VEHICLE_CMD_DO_SET_MODE,
                param1=1.0,   # base mode: custom
                param2=6.0,   # custom main mode: offboard
            )
            # Arm the vehicle
            self._send_vehicle_command(
                VehicleCommand.VEHICLE_CMD_COMPONENT_ARM_DISARM,
                param1=1.0,   # 1 = arm, 0 = disarm
            )

        if self._counter < 11:
            self._counter += 1

    def _publish_offboard_control_mode(self) -> None:
        msg = OffboardControlMode()
        msg.position = True       # position control is active
        msg.velocity = False
        msg.acceleration = False
        msg.attitude = False
        msg.body_rate = False
        msg.timestamp = int(self.get_clock().now().nanoseconds / 1000)
        self.offboard_mode_pub.publish(msg)

    def _publish_trajectory_setpoint(self) -> None:
        msg = TrajectorySetpoint()
        # NED frame: z = -5.0 means 5 metres above the home point
        msg.position = [0.0, 0.0, -5.0]
        msg.yaw = -3.14159  # radians, range [-π, π]
        msg.timestamp = int(self.get_clock().now().nanoseconds / 1000)
        self.trajectory_pub.publish(msg)

    def _send_vehicle_command(
        self,
        command: int,
        param1: float = 0.0,
        param2: float = 0.0,
    ) -> None:
        msg = VehicleCommand()
        msg.command = command
        msg.param1 = param1
        msg.param2 = param2
        msg.target_system = 1
        msg.target_component = 1
        msg.source_system = 1
        msg.source_component = 1
        msg.from_external = True
        msg.timestamp = int(self.get_clock().now().nanoseconds / 1000)
        self.command_pub.publish(msg)


def main() -> None:
    rclpy.init()
    node = OffboardControlNode()
    rclpy.spin(node)
    node.destroy_node()
    rclpy.shutdown()


if __name__ == '__main__':
    main()

Running the example

1

Start the uXRCE-DDS agent

MicroXRCEAgent udp4 --port 8888
2

Start PX4 SITL

make px4_sitl gz_x500
The SITL build starts the uXRCE-DDS client automatically.
3

Create and build a ROS 2 workspace

mkdir -p ~/ws_offboard/src && cd ~/ws_offboard/src
git clone https://github.com/PX4/px4_msgs.git
# Place your node package here, then build:
cd ..
source /opt/ros/humble/setup.bash
colcon build
source install/local_setup.bash
4

Run your node

ros2 run <your_package> offboard_control
The vehicle arms, ascends to 5 metres, and holds position. Use QGroundControl or an RC transmitter to regain manual control at any time.
QGroundControl must be connected to PX4 before you attempt to arm, unless you have disabled the safety check that requires a ground station or RC link. This ensures you always have a fallback path to manual control.

Key constraints

  • OffboardControlMode must arrive at 10 Hz or higher. The minimum to stay in offboard mode is ~2 Hz, but the arming check requires a healthy stream established before the mode switch.
  • Set only one control dimension to true in OffboardControlMode at a time. Mixing position and velocity control simultaneously is not supported in this message — use separate fields for different axes when needed.
  • Timestamps in all messages use microseconds since system boot, expressed as an integer: int(node.get_clock().now().nanoseconds / 1000).
  • Positions are in the NED frame: X = North, Y = East, Z = Down. Altitude above home is a negative Z value.

Build docs developers (and LLMs) love