docs: add Remote ID in-flight failsafe documentation

Update safety.md, remote_id.md, and releases/main.md to document the extended COM_ARM_ODID parameter  and the new in-flight failsafe behaviour that will be introduced in PX4 v1.18.
This commit is contained in:
gguidone
2026-04-15 10:52:25 +02:00
committed by Gennaro Guidone
parent 6e980423e5
commit 4fee468f3f
4 changed files with 29 additions and 18 deletions
+16 -1
View File
@@ -251,6 +251,21 @@ The relevant parameters are shown below:
| ---------------------------------------------------------------------------- | ---------------------------------------------------------------- | | ---------------------------------------------------------------------------- | ---------------------------------------------------------------- |
| [NAV_TRAFF_AVOID](../advanced_config/parameter_reference.md#NAV_TRAFF_AVOID) | Set the failsafe action: Disabled, Warn, Return mode, Land mode. | | [NAV_TRAFF_AVOID](../advanced_config/parameter_reference.md#NAV_TRAFF_AVOID) | Set the failsafe action: Disabled, Warn, Return mode, Land mode. |
## Remote ID Failsafe
<Badge type="tip" text="PX4 v1.18" />
The Remote ID failsafe is triggered when the [Remote ID (Open Drone ID)](../peripherals/remote_id.md) module is missing or loses its heartbeat while the vehicle is armed and airborne.
The failsafe action and arming behaviour are both configured by a single parameter:
| Parameter | Description |
| ----------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ |
| <a id="COM_ARM_ODID"></a>[COM_ARM_ODID](../advanced_config/parameter_reference.md#COM_ARM_ODID) | Remote ID arming check and in-flight failsafe. `0`: Disabled (default), `1`: Warning only, `2`: Error only, `3`: Return, `4`: Land, `5`: Terminate. |
Values `2``5` prevent arming when the Remote ID system is not present and healthy.
Values `3``5` also trigger the configured failsafe action if the Remote ID system is missing or unhealthy while airborne.
## Quad-chute Failsafe ## Quad-chute Failsafe
Failsafe for when a VTOL vehicle can no longer fly in fixed-wing mode, perhaps due to the failure of a pusher motor, airspeed sensor, or control surface. Failsafe for when a VTOL vehicle can no longer fly in fixed-wing mode, perhaps due to the failure of a pusher motor, airspeed sensor, or control surface.
@@ -441,7 +456,7 @@ These parameters can be used to set conditions that prevent arming.
| <a id="COM_ARM_MIS_REQ"></a>[COM_ARM_MIS_REQ](../advanced_config/parameter_reference.md#COM_ARM_MIS_REQ) | Require valid mission to arm. `0`: Disabled (default), `1`: Enabled . | | <a id="COM_ARM_MIS_REQ"></a>[COM_ARM_MIS_REQ](../advanced_config/parameter_reference.md#COM_ARM_MIS_REQ) | Require valid mission to arm. `0`: Disabled (default), `1`: Enabled . |
| <a id="COM_ARM_SDCARD"></a>[COM_ARM_SDCARD](../advanced_config/parameter_reference.md#COM_ARM_SDCARD) | Require SD card to arm. `0`: Disabled (default), `1`: Warning, `2`: Enabled. | | <a id="COM_ARM_SDCARD"></a>[COM_ARM_SDCARD](../advanced_config/parameter_reference.md#COM_ARM_SDCARD) | Require SD card to arm. `0`: Disabled (default), `1`: Warning, `2`: Enabled. |
| <a id="COM_ARM_AUTH_REQ"></a>[COM_ARM_AUTH_REQ](../advanced_config/parameter_reference.md#COM_ARM_AUTH_REQ) | Requires arm authorisation from an external (MAVLink) system. Flag to allow arming (at all). `1`: Enabled, `0`: Disabled (default). Associated configuration parameters are prefixed with `COM_ARM_AUTH_`. | | <a id="COM_ARM_AUTH_REQ"></a>[COM_ARM_AUTH_REQ](../advanced_config/parameter_reference.md#COM_ARM_AUTH_REQ) | Requires arm authorisation from an external (MAVLink) system. Flag to allow arming (at all). `1`: Enabled, `0`: Disabled (default). Associated configuration parameters are prefixed with `COM_ARM_AUTH_`. |
| <a id="COM_ARM_ODID"></a>[COM_ARM_ODID](../advanced_config/parameter_reference.md#COM_ARM_ODID) | Require healthy Remote ID system to arm. `0`: Disabled (default), `1`: Warning, `2`: Enabled. | | <a id="COM_ARM_ODID"></a>[COM_ARM_ODID](../advanced_config/parameter_reference.md#COM_ARM_ODID) | Remote ID arming check and in-flight failsafe. `0`: Disabled (default), `1`: Warning only, `2`: Error only, `3`: Return, `4`: Land, `5`: Terminate. See [Remote ID Failsafe](#remote-id-failsafe). |
In addition there are a number of parameters that configure system and sensor limits that make prevent arming if exceeded: [COM_CPU_MAX](../advanced_config/parameter_reference.md#COM_CPU_MAX), [COM_ARM_IMU_ACC](../advanced_config/parameter_reference.md#COM_ARM_IMU_ACC), [COM_ARM_IMU_GYR](../advanced_config/parameter_reference.md#COM_ARM_IMU_GYR), [COM_ARM_MAG_ANG](../advanced_config/parameter_reference.md#COM_ARM_MAG_ANG), [COM_ARM_MAG_STR](../advanced_config/parameter_reference.md#COM_ARM_MAG_STR). In addition there are a number of parameters that configure system and sensor limits that make prevent arming if exceeded: [COM_CPU_MAX](../advanced_config/parameter_reference.md#COM_CPU_MAX), [COM_ARM_IMU_ACC](../advanced_config/parameter_reference.md#COM_ARM_IMU_ACC), [COM_ARM_IMU_GYR](../advanced_config/parameter_reference.md#COM_ARM_IMU_GYR), [COM_ARM_MAG_ANG](../advanced_config/parameter_reference.md#COM_ARM_MAG_ANG), [COM_ARM_MAG_STR](../advanced_config/parameter_reference.md#COM_ARM_MAG_STR).
+11 -6
View File
@@ -143,13 +143,18 @@ The [CAN Remote ID Not Working](../peripherals/remote_id.md#can-remote-id-not-wo
There is no need to explicitly enable Remote ID (supported Remote ID messages are either streamed by default or must be requested in the current implementation, even if no remote ID is connected). There is no need to explicitly enable Remote ID (supported Remote ID messages are either streamed by default or must be requested in the current implementation, even if no remote ID is connected).
### Prevent Arming based on Remote ID ### Remote ID Arming Check and In-Flight Failsafe
To only allow arming when a Remote ID is ready, [set](../advanced_config/parameters.md#conditional-parameters) the parameter [COM_ARM_ODID](#COM_ARM_ODID) to `2` (it is disabled by default). <Badge type="tip" text="PX4 v1.18" />
| Parameter | Description | The [COM_ARM_ODID](../advanced_config/parameter_reference.md#COM_ARM_ODID) parameter configures both the arming check and the in-flight failsafe action when the Remote ID system is missing or unhealthy:
| ----------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="COM_ARM_ODID"></a>[COM_ARM_ODID](../advanced_config/parameter_reference.md#COM_ARM_ODID) | Enable Drone ID system detection and health check. `0`: Disable (default), `1`: Warn if Remote ID not detected but still allow arming, `2`: Only allow arming if Remote ID is present. | | Parameter | Description |
| ----------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ |
| <a id="COM_ARM_ODID"></a>[COM_ARM_ODID](../advanced_config/parameter_reference.md#COM_ARM_ODID) | `0`: Disabled (default), `1`: Warning only, `2`: Error only, `3`: Return, `4`: Land, `5`: Terminate. |
Values `2``5` prevent arming when the Remote ID system is not present and healthy.
Values `3``5` also trigger the configured failsafe action if the Remote ID system is missing or unhealthy while airborne.
## Module Broadcast Testing ## Module Broadcast Testing
@@ -173,7 +178,7 @@ The following message can be streamed on request (using [MAV_CMD_SET_MESSAGE_INT
- [OPEN_DRONE_ID_BASIC_ID](https://mavlink.io/en/messages/common.html#OPEN_DRONE_ID_BASIC_ID) - UAV identity information (essentially a serial number) - [OPEN_DRONE_ID_BASIC_ID](https://mavlink.io/en/messages/common.html#OPEN_DRONE_ID_BASIC_ID) - UAV identity information (essentially a serial number)
- PX4 v1.14 specifies a serial number ([MAV_ODID_ID_TYPE_SERIAL_NUMBER](https://mavlink.io/en/messages/common.html#MAV_ODID_ID_TYPE_SERIAL_NUMBER)) but does not use the required format (ANSI/CTA-2063 format). - PX4 v1.14 specifies a serial number ([MAV_ODID_ID_TYPE_SERIAL_NUMBER](https://mavlink.io/en/messages/common.html#MAV_ODID_ID_TYPE_SERIAL_NUMBER)) but does not use the required format (ANSI/CTA-2063 format).
PX4 prevents arming based on Remote ID health if parameter [COM_ARM_ODID](../advanced_config/parameter_reference.md#COM_ARM_ODID) is set to `2`. PX4 can prevent arming and/or trigger an in-flight failsafe based on Remote ID health via the [COM_ARM_ODID](../advanced_config/parameter_reference.md#COM_ARM_ODID) parameter.
The UAV will then require `HEARTBEAT` messages from the Remote ID as a precondition for arming the UAV. The UAV will then require `HEARTBEAT` messages from the Remote ID as a precondition for arming the UAV.
You can also set the parameter to `1` to warn but still allow arming when Remote ID `HEARTBEAT` messages are not detected. You can also set the parameter to `1` to warn but still allow arming when Remote ID `HEARTBEAT` messages are not detected.
+1
View File
@@ -40,6 +40,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
### Common ### Common
- [Remote ID (Open Drone ID) in-flight failsafe](../peripherals/remote_id.md): extended [COM_ARM_ODID](../advanced_config/parameter_reference.md#COM_ARM_ODID) to also trigger a configurable failsafe action (Return, Land, or Terminate) if the Remote ID heartbeat is lost while airborne. Users previously on `COM_ARM_ODID=2` retain the same arming behaviour; set to `3` or higher to enable the in-flight action. ([PX4-Autopilot#27029](https://github.com/PX4/PX4-Autopilot/pull/27029))
- [QGroundControl Bootloader Update](../advanced_config/bootloader_update.md#qgc-bootloader-update-sys-bl-update) via the [SYS_BL_UPDATE](../advanced_config/parameter_reference.md#SYS_BL_UPDATE) parameter has been re-enabled after being broken for a number of releases. ([PX4-Autopilot#25032: build: romf: fix generation of rc.board_bootloader_upgrade](https://github.com/PX4/PX4-Autopilot/pull/25032)). - [QGroundControl Bootloader Update](../advanced_config/bootloader_update.md#qgc-bootloader-update-sys-bl-update) via the [SYS_BL_UPDATE](../advanced_config/parameter_reference.md#SYS_BL_UPDATE) parameter has been re-enabled after being broken for a number of releases. ([PX4-Autopilot#25032: build: romf: fix generation of rc.board_bootloader_upgrade](https://github.com/PX4/PX4-Autopilot/pull/25032)).
- [Feature: Allow prioritization of manual control inputs based on their instance number in ascending or descending order](../config/manual_control.md#px4-configuration). ([PX4-Autopilot#25602: Ascending and descending manual control input priorities](https://github.com/PX4/PX4-Autopilot/pull/25602)). - [Feature: Allow prioritization of manual control inputs based on their instance number in ascending or descending order](../config/manual_control.md#px4-configuration). ([PX4-Autopilot#25602: Ascending and descending manual control input priorities](https://github.com/PX4/PX4-Autopilot/pull/25602)).
+1 -11
View File
@@ -613,16 +613,7 @@ parameters:
COM_ARM_ODID: COM_ARM_ODID:
description: description:
short: Open Drone ID system check and in-flight failsafe short: Open Drone ID system check and in-flight failsafe
long: |- long: Actions other than warning also prevent arming.
Configures both the arming check and the in-flight failsafe for the
Open Drone ID (Remote ID) system.
Warning: warns at arming but does not block it, and takes no in-flight action.
Error only: blocks arming without the ODID system present and healthy, but
takes no automated action if the system is lost while airborne.
Return / Land / Terminate: block arming without the ODID system present and
healthy, and trigger the corresponding failsafe action if the system is lost
while airborne (heartbeat timeout > 3 s).
type: enum type: enum
values: values:
0: Disabled 0: Disabled
@@ -632,7 +623,6 @@ parameters:
4: Land 4: Land
5: Terminate 5: Terminate
default: 0 default: 0
increment: 1
COM_ARM_TRAFF: COM_ARM_TRAFF:
description: description:
short: Enable Traffic Avoidance system detection check short: Enable Traffic Avoidance system detection check