Skip to content

Offboard Mode (Generic/All Frames)

The vehicle obeys position, velocity, acceleration, attitude, attitude rates or thrust/torque setpoints provided by some source that is external to the flight stack, such as a companion computer. The setpoints may be provided using MAVLink (or a MAVLink API such as MAVSDK) or by ROS 2.

PX4 requires that the external controller provides a continuous 2Hz "proof of life" signal, by streaming any of the supported MAVLink setpoint messages or the ROS 2 OffboardControlMode message. PX4 enables offboard control only after receiving the signal for more than a second, and will regain control if the signal stops.

INFO

  • This mode requires position or pose/attitude information - e.g. GPS, optical flow, visual-inertial odometry, mocap, etc.
  • RC control is disabled except to change modes (you can also fly without any manual controller at all by setting the parameter COM_RC_IN_MODE to 4: Stick input disabled).
  • The vehicle must be already be receiving a stream of MAVLink setpoint messages or ROS 2 OffboardControlMode messages before arming in offboard mode or switching to offboard mode when flying.
  • The vehicle will exit offboard mode if MAVLink setpoint messages or OffboardControlMode are not received at a rate of > 2Hz.
  • Not all coordinate frames and field values allowed by MAVLink are supported for all setpoint messages and vehicles. Read the sections below carefully to ensure only supported values are used.

Description

Offboard mode is used for controlling vehicle movement and attitude, by setting position, velocity, acceleration, attitude, attitude rates or thrust/torque setpoints.

PX4 must receive a stream of MAVLink setpoint messages or the ROS 2 OffboardControlMode at 2 Hz as proof that the external controller is healthy. The stream must be sent for at least a second before PX4 will arm in offboard mode, or switch to offboard mode when flying. If the rate falls below 2Hz while under external control PX4 will switch out of offboard mode after a timeout (COM_OF_LOSS_T), and attempt to land or perform some other failsafe action. The action depends on whether or not RC control is available, and is defined in the parameter COM_OBL_RC_ACT.

When using MAVLink the setpoint messages convey both the signal to indicate that the external source is "alive", and the setpoint value itself. In order to hold position in this case the vehicle must receive a stream of setpoints for the current position.

When using ROS 2 the proof that the external source is alive is provided by a stream of OffboardControlMode messages, while the actual setpoint is provided by publishing to one of the setpoint uORB topics, such as TrajectorySetpoint. In order to hold position in this case the vehicle must receive a stream of OffboardControlMode but would only need the TrajectorySetpoint once.

Note that offboard mode only supports a very limited set of MAVLink commands and messages. Operations, like taking off, landing, return to launch, may be best handled using the appropriate modes. Operations like uploading, downloading missions can be performed in any mode.

ROS 2 Messages

The following ROS 2 messages and their particular fields and field values are allowed for the specified frames. In addition to providing heartbeat functionality, OffboardControlMode has two other main purposes:

  1. Controls the level of the PX4 control architecture at which offboard setpoints must be injected, and disables the bypassed controllers.
  2. Determines which valid estimates (position or velocity) are required, and also which setpoint messages should be used.

The OffboardControlMode message is defined as shown.

sh
# Off-board control mode

uint64 timestamp		# time since system start (microseconds)

bool position
bool velocity
bool acceleration
bool attitude
bool body_rate
bool thrust_and_torque
bool direct_actuator

The fields are ordered in terms of priority such that position takes precedence over velocity and later fields, velocity takes precedence over acceleration, and so on. The first field that has a non-zero value (from top to bottom) defines what valid estimate is required in order to use offboard mode, and the setpoint message(s) that can be used. For example, if the acceleration field is the first non-zero value, then PX4 requires a valid velocity estimate, and the setpoint must be specified using the TrajectorySetpoint message.

desired control quantityposition fieldvelocity fieldacceleration fieldattitude fieldbody_rate fieldthrust_and_torque fielddirect_actuator fieldrequired estimaterequired message
position (NED)------positionTrajectorySetpoint
velocity (NED)-----velocityTrajectorySetpoint
acceleration (NED)----velocityTrajectorySetpoint
attitude (FRD)---noneVehicleAttitudeSetpoint
body_rate (FRD)--noneVehicleRatesSetpoint
thrust and torque (FRD)-noneVehicleThrustSetpoint and VehicleTorqueSetpoint
direct motors and servosnoneActuatorMotors and ActuatorServos

where ✓ means that the bit is set, ✗ means that the bit is not set and - means that the bit is value is irrelevant.

INFO

Before using offboard mode with ROS 2, please spend a few minutes understanding the different frame conventions that PX4 and ROS 2 use.

Copter

  • px4_msgs::msg::TrajectorySetpoint

    • The following input combinations are supported:

      • Position setpoint (position different from NaN). Non-NaN values of velocity and acceleration are used as feedforward terms for the inner loop controllers.
      • Velocity setpoint (velocity different from NaN and position set to NaN). Non-NaN values acceleration are used as feedforward terms for the inner loop controllers.
      • Acceleration setpoint (acceleration different from NaN and position and velocity set to NaN)
    • All values are interpreted in NED (Nord, East, Down) coordinate system and the units are [m], [m/s] and [m/s^2] for position, velocity and acceleration, respectively.

  • px4_msgs::msg::VehicleAttitudeSetpoint

    • The following input combination is supported:

      • quaternion q_d + thrust setpoint thrust_body. Non-NaN values of yaw_sp_move_rate are used as feedforward terms expressed in Earth frame and in [rad/s].
    • The quaternion represents the rotation between the drone body FRD (front, right, down) frame and the NED frame. The thrust is in the drone body FRD frame and expressed in normalized [-1, 1] values.

  • px4_msgs::msg::VehicleRatesSetpoint

    • The following input combination is supported:

      • roll, pitch, yaw and thrust_body.
    • All the values are in the drone body FRD frame. The rates are in [rad/s] while thrust_body is normalized in [-1, 1].

Generic Vehicle

The following offboard control modes bypass all internal PX4 control loops and should be used with great care.

The following MAVLink messages and their particular fields and field values are allowed for the specified vehicle frames.

Copter/VTOL

  • SET_POSITION_TARGET_LOCAL_NED

    • The following input combinations are supported:

      • Position setpoint (only x, y, z)
      • Velocity setpoint (only vx, vy, vz)
      • Acceleration setpoint (only afx, afy, afz)
      • Position setpoint and velocity setpoint (the velocity setpoint is used as feedforward; it is added to the output of the position controller and the result is used as the input to the velocity controller).
      • Position setpoint and velocity setpoint and acceleration (the velocity and the acceleration setpoints are used as feedforwards; the velocity setpoint is added to the output of the position controller and the result is used as the input to the velocity controller; the acceleration setpoint is added to the output of the velocity controller and the result used to compute the thrust vector).
    • PX4 supports the following coordinate_frame values (only): MAV_FRAME_LOCAL_NED and MAV_FRAME_BODY_NED.

  • SET_POSITION_TARGET_GLOBAL_INT

    • The following input combinations are supported:

      • Position setpoint (only lat_int, lon_int, alt)

      • Velocity setpoint (only vx, vy, vz)

      • Thrust setpoint (only afx, afy, afz)

        INFO

        Acceleration setpoint values are mapped to create a normalized thrust setpoint (i.e. acceleration setpoints are not "properly" supported).

      • Position setpoint and velocity setpoint (the velocity setpoint is used as feedforward; it is added to the output of the position controller and the result is used as the input to the velocity controller).

    • PX4 supports the following coordinate_frame values (only): MAV_FRAME_GLOBAL.

  • SET_ATTITUDE_TARGET

    • The following input combinations are supported:
      • Attitude/orientation (SET_ATTITUDE_TARGET.q) with thrust setpoint (SET_ATTITUDE_TARGET.thrust).
      • Body rate (SET_ATTITUDE_TARGET .body_roll_rate ,.body_pitch_rate, .body_yaw_rate) with thrust setpoint (SET_ATTITUDE_TARGET.thrust).

Fixed-wing

  • SET_POSITION_TARGET_LOCAL_NED

    • The following input combinations are supported (via type_mask):

      • Position setpoint (x, y, z only; velocity and acceleration setpoints are ignored).

        • Specify the type of the setpoint in type_mask (if these bits are not set the vehicle will fly in a flower-like pattern):

          INFO

          Some of the setpoint type values below are not part of the MAVLink standard for the type_mask field.

          The values are:

          • 292: Gliding setpoint. This configures TECS to prioritize airspeed over altitude in order to make the vehicle glide when there is no thrust (i.e. pitch is controlled to regulate airspeed). It is equivalent to setting type_mask as POSITION_TARGET_TYPEMASK_Z_IGNORE, POSITION_TARGET_TYPEMASK_VZ_IGNORE, POSITION_TARGET_TYPEMASK_AZ_IGNORE.
          • 4096: Takeoff setpoint.
          • 8192: Land setpoint.
          • 12288: Loiter setpoint (fly a circle centred on setpoint).
          • 16384: Idle setpoint (zero throttle, zero roll / pitch).
    • PX4 supports the coordinate frames (coordinate_frame field): MAV_FRAME_LOCAL_NED and MAV_FRAME_BODY_NED.

  • SET_POSITION_TARGET_GLOBAL_INT

    • The following input combinations are supported (via type_mask):

      • Position setpoint (only lat_int, lon_int, alt)

        • Specify the type of the setpoint in type_mask (if these bits are not set the vehicle will fly in a flower-like pattern):

          INFO

          The setpoint type values below are not part of the MAVLink standard for the type_mask field.

          The values are:

          • 4096: Takeoff setpoint.
          • 8192: Land setpoint.
          • 12288: Loiter setpoint (fly a circle centred on setpoint).
          • 16384: Idle setpoint (zero throttle, zero roll / pitch).
    • PX4 supports the following coordinate_frame values (only): MAV_FRAME_GLOBAL.

  • SET_ATTITUDE_TARGET

    • The following input combinations are supported:
      • Attitude/orientation (SET_ATTITUDE_TARGET.q) with thrust setpoint (SET_ATTITUDE_TARGET.thrust).
      • Body rate (SET_ATTITUDE_TARGET .body_roll_rate ,.body_pitch_rate, .body_yaw_rate) with thrust setpoint (SET_ATTITUDE_TARGET.thrust).

Rover

  • SET_POSITION_TARGET_LOCAL_NED

    • The following input combinations are supported (in type_mask):

      • Position setpoint (only x, y, z)

        • Specify the type of the setpoint in type_mask:

          INFO

          The setpoint type values below are not part of the MAVLink standard for the type_mask field. ::

          The values are:

          • 12288: Loiter setpoint (vehicle stops when close enough to setpoint).
      • Velocity setpoint (only vx, vy, vz)

    • PX4 supports the coordinate frames (coordinate_frame field): MAV_FRAME_LOCAL_NED and MAV_FRAME_BODY_NED.

  • SET_POSITION_TARGET_GLOBAL_INT

    • The following input combinations are supported (in type_mask):

      • Position setpoint (only lat_int, lon_int, alt)
    • Specify the type of the setpoint in type_mask (not part of the MAVLink standard). The values are:

      • Following bits not set then normal behaviour.
      • 12288: Loiter setpoint (vehicle stops when close enough to setpoint).
    • PX4 supports the coordinate frames (coordinate_frame field): MAV_FRAME_GLOBAL.

  • SET_ATTITUDE_TARGET

    • The following input combinations are supported:
      • Attitude/orientation (SET_ATTITUDE_TARGET.q) with thrust setpoint (SET_ATTITUDE_TARGET.thrust).

        INFO

        Only the yaw setting is actually used/extracted.

Offboard Parameters

Offboard mode is affected by the following parameters:

ParameterDescription
COM_OF_LOSS_TTime-out (in seconds) to wait when offboard connection is lost before triggering offboard lost failsafe (COM_OBL_RC_ACT)
COM_OBL_RC_ACTFlight mode to switch to if offboard control is lost (Values are - 0: Position, 1: Altitude, 2: Manual, 3: *Return, 4: *Land*).
COM_RC_OVERRIDEControls whether stick movement on a multicopter (or VTOL in MC mode) causes a mode change to Position mode. This is not enabled for offboard mode by default.
COM_RC_STICK_OVThe amount of stick movement that causes a transition to Position mode (if COM_RC_OVERRIDE is enabled).
COM_RCL_EXCEPTSpecify modes in which RC loss is ignored and the failsafe action not triggered. Set bit 2 to ignore RC loss in Offboard mode.

Developer Resources

Typically developers do not directly work at the MAVLink layer, but instead use a robotics API like MAVSDK or ROS (these provide a developer friendly API, and take care of managing and maintaining connections, sending messages and monitoring responses - the minutiae of working with Offboard mode and MAVLink).

The following resources may be useful for a developer audience: