diff --git a/docs/en/flight_modes/offboard.md b/docs/en/flight_modes/offboard.md index 69cd69dfc3..a29dd722c6 100644 --- a/docs/en/flight_modes/offboard.md +++ b/docs/en/flight_modes/offboard.md @@ -2,17 +2,29 @@ +:::: warning + +Offboard control with ROS 2 requires _significant care_ to ensure that it is used safely. +Please read [ROS 2 Offboard Control](#ros-2-offboard-control) carefully to fully understand the risks involved when using it. +A good understanding of [PX4 controller diagrams](../flight_stack/controller_diagrams.md) is advised. + +::: tip +[PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) provides a safer alternative. +::: + +:::: + 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](https://mavsdk.mavlink.io/)) or by [ROS 2](../ros2/index.md). 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](../msg_docs/OffboardControlMode.md) message. -PX4 enables offboard control only after receiving the signal for more than a second, and will regain control if the signal stops. +PX4 enables switching to offboard control mode only after receiving the signal for more than a second, and will failsafe (controlled by [COM_OBL_RC_ACT](../advanced_config/parameter_reference.md#COM_OBL_RC_ACT)) if the signal stops. ::: info -- This mode requires position or pose/attitude information - e.g. GPS, optical flow, visual-inertial odometry, mocap, etc. +- This mode requires position or pose/attitude information - e.g. GPS, optical flow, visual-inertial odometry, mocap, etc. depending on the type of offboard setpoints that the external controller sends. - Manual 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](../advanced_config/parameter_reference.md#COM_RC_IN_MODE) to `4: Disable manual control`). -- The vehicle must be already be receiving a stream of MAVLink setpoint messages or ROS 2 [OffboardControlMode](../msg_docs/OffboardControlMode.md) messages before arming in offboard mode or switching to offboard mode when flying. +- The vehicle must already be receiving a stream of MAVLink setpoint messages or ROS 2 [OffboardControlMode](../msg_docs/OffboardControlMode.md) 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. @@ -38,13 +50,37 @@ Note that offboard mode only supports a very limited set of MAVLink commands and 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 +## ROS 2 Offboard Control + +This section describes how to perform offboard control through one of the direct ROS 2 interfaces: UXRCE-DDS or Zenoh. + +When using direct ROS 2 offboard control, PX4 setpoint messages generated by external controllers are injected into the [PX4 control pipeline](../flight_stack/controller_diagrams.md). +Because messages from internal and external controllers are indistinguishable within PX4, precise synchronization is required in order to avoid the controllers writing conflicting messages to the same topic. + +In Offboard mode (only), an external system can use [`OffboardControlMode`](#the-offboardcontrolmode-px4-message) to specify which setpoint topics PX4 should publish/not publish, allowing them to be written safely by an external controller. + +::: warning + +PX4 has no means of filtering and distinguishing ROS 2 messages from internal messages, in any mode. +In order to interwork safely, the external controller must: + +- Publish PX4 setpoint messages **ONLY** in Offboard mode. +- Specify which setpoints it will write using the `OffboardControlMode` topic. +- Stream the `OffboardControlMode` topic as a keep-alive signal. +- Stream the setpoints it wants: unlike with MAVLink, PX4 won't trigger a failsafe if setpoints aren't sent regularly. + +If external setpoints are sent in any other flight mode, or they overwrite topics that have not been disabled by PX4 when in offboard mode, collisions are likely. +This will result in unexpected, and possibly catastrophic, behaviour. + +::: + +### The `OffboardControlMode` PX4 message 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](../flight_stack/controller_diagrams.md) 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. +1. Controls which internal PX4 control modules of the [PX4 control architecture](../flight_stack/controller_diagrams.md) shall remain active and which ones shall be disabled when the vehicle is in Offboard Mode. +2. Determines which valid estimates (position, velocity, etc.) are required. The `OffboardControlMode` message is defined as shown. @@ -69,33 +105,46 @@ For rovers see the [rover section](#rover). 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. +For example, if the `acceleration` field is the first non-zero value, then PX4 requires a valid `attitude estimate`, and the setpoint must be specified using the `TrajectorySetpoint` message. | desired control quantity | position field | velocity field | acceleration field | attitude field | body_rate field | thrust_and_torque field | direct_actuator field | required estimate | required message | | ------------------------ | -------------- | -------------- | ------------------ | -------------- | --------------- | ----------------------- | --------------------- | ----------------- | ------------------------------------------------------------------------------------------------------------------------------- | | position (NED) | ✓ | - | - | - | - | - | - | position | [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) | | velocity (NED) | ✗ | ✓ | - | - | - | - | - | velocity | [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) | -| acceleration (NED) | ✗ | ✗ | ✓ | - | - | - | - | velocity | [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) | -| attitude (FRD) | ✗ | ✗ | ✗ | ✓ | - | - | - | none | [VehicleAttitudeSetpoint](../msg_docs/VehicleAttitudeSetpoint.md) | -| body_rate (FRD) | ✗ | ✗ | ✗ | ✗ | ✓ | - | - | none | [VehicleRatesSetpoint](../msg_docs/VehicleRatesSetpoint.md) | +| acceleration (NED) | ✗ | ✗ | ✓ | - | - | - | - | attitude | [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) | +| attitude (FRD) | ✗ | ✗ | ✗ | ✓ | - | - | - | attitude | [VehicleAttitudeSetpoint](../msg_docs/VehicleAttitudeSetpoint.md) | +| body_rate (FRD) | ✗ | ✗ | ✗ | ✗ | ✓ | - | - | angular velocity | [VehicleRatesSetpoint](../msg_docs/VehicleRatesSetpoint.md) | | thrust and torque (FRD) | ✗ | ✗ | ✗ | ✗ | ✗ | ✓ | - | none | [VehicleThrustSetpoint](../msg_docs/VehicleThrustSetpoint.md) and [VehicleTorqueSetpoint](../msg_docs/VehicleTorqueSetpoint.md) | | direct motors and servos | ✗ | ✗ | ✗ | ✗ | ✗ | ✗ | ✓ | none | [ActuatorMotors](../msg_docs/ActuatorMotors.md) and [ActuatorServos](../msg_docs/ActuatorServos.md) | -where ✓ means that the bit is set, ✘ means that the bit is not set and `-` means that the bit is value is irrelevant. +where ✓ means that the bit is set, ✘ means that the bit is not set and `-` means that the bit value is irrelevant. ::: info Before using offboard mode with ROS 2, please spend a few minutes understanding the different [frame conventions](../ros2/user_guide.md#ros-2-px4-frame-conventions) that PX4 and ROS 2 use. ::: -### Copter +In the following, the different setpoint messages for the main supported airframes are explained. +For fixed-wing offboard control, please refer to the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md). + +### Multicopters - [px4_msgs::msg::TrajectorySetpoint](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/TrajectorySetpoint.msg) - 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. + - Velocity setpoint (`velocity` different from `NaN` and `position` set to `NaN`). Non-`NaN` values of 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. + - All values are interpreted in NED (North, East, Down) coordinate system and the units are `[m]`, `[m/s]` and `[m/s^2]` for position, velocity and acceleration, respectively. + + ::: warning + + Position, velocity and acceleration control for multicopters are all handled by the `mc_pos_control` module. + This module is enabled if any of `position`, `velocity` and `acceleration` fields are set to true. + However, only the content of the `TrajectorySetpoint` messages determines which of the three controllers shall run. + + This means that even if `OffboardControlMode` messages carry the intention of velocity control (only `velocity` field is set) but non-`NaN` position values are sent in the `TrajectorySetpoint` messages, then PX4 will keep running the position controller. + + ::: - [px4_msgs::msg::VehicleAttitudeSetpoint](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleAttitudeSetpoint.msg) - The following input combination is supported: @@ -194,13 +243,11 @@ The following offboard control modes bypass all internal PX4 control loops and s - [px4_msgs::msg::ActuatorMotors](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ActuatorMotors.msg) + [px4_msgs::msg::ActuatorServos](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ActuatorServos.msg) - You directly control the motor outputs and/or servo outputs. - - Currently works at lower level than then `control_allocator` module. - Do not publish these messages when not in offboard mode. - All the values normalized in `[-1, 1]`. For outputs that do not support negative values, negative entries map to `NaN`. - `NaN` maps to disarmed. -## MAVLink Messages +## MAVLink Offboard Control The following MAVLink messages and their particular fields and field values are allowed for the specified vehicle frames.