fix(commander): prevent arming if enabled parachute check fails

This commit is contained in:
Matthias Grob
2026-05-17 12:10:37 +02:00
committed by Gennaro Guidone
parent 4caac66328
commit fcb627f572
7 changed files with 48 additions and 79 deletions
+1 -1
View File
@@ -288,7 +288,7 @@ The parachute health failsafe is triggered when a [MAVLink parachute](../periphe
| Parameter | Description |
| -------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ |
| <a id="COM_PARACHUTE"></a>[COM_PARACHUTE](../advanced_config/parameter_reference.md#COM_PARACHUTE) | Parachute system monitoring and failsafe action. `0`: Disabled (default), `1`: Warning only, `2`: Error only (prevent arming), `3`: Return, `4`: Land.<br><br>On failsafe:<br>- `Error`, `Return`, and `Land` prevent arming.<br>- `Return` and `Land` start the associated action/mode when airborne. |
| <a id="COM_PARACHUTE"></a>[COM_PARACHUTE](../advanced_config/parameter_reference.md#COM_PARACHUTE) | Parachute system monitoring and failsafe action.<br>`0`: Disabled (default), `1`: [Warning](#act_warn), `2`: [Return](#act_return), `3`: [Land](#act_land).<br><br>- Everything but `Disabled` prevents arming with a failing check.<br>- [Return](#act_return) and [Land](#act_land) start the associated action when a failure happens in-flight. |
## Quad-chute Failsafe
+1 -1
View File
@@ -75,7 +75,7 @@ You then need to ensure that the parachute pin will be set to a value that will
PX4 will trigger a connected and healthy parachute on failsafe by sending the command [MAV_CMD_DO_PARACHUTE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_PARACHUTE) with the [PARACHUTE_RELEASE](https://mavlink.io/en/messages/common.html#PARACHUTE_ACTION) action.
MAVLink parachute support is enabled by setting the parameter [COM_PARACHUTE](../advanced_config/parameter_reference.md#COM_PARACHUTE) to a non-zero value.
The parameter also configures the arming check and in-flight failsafe action when the parachute system is missing or unhealthy (see [Parachute Health Failsafe](../config/safety.md#parachute-health-failsafe)).
The parameter also configures the arming check and in-flight failsafe action when the parachute system is missing or unhealthy, see [Parachute Health Failsafe](../config/safety.md#parachute-health-failsafe).
PX4 will then indicate parachute status using the [MAV_SYS_STATUS_RECOVERY_SYSTEM](https://mavlink.io/en/messages/common.html#MAV_SYS_STATUS_RECOVERY_SYSTEM) bit in the [SYS_STATUS](https://mavlink.io/en/messages/common.html#SYS_STATUS) extended onboard control sensors fields:
+1 -1
View File
@@ -44,7 +44,6 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
- [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)).
- [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)).
- [Parachute health failsafe](../peripherals/parachute.md): extended [COM_PARACHUTE](../advanced_config/parameter_reference.md#COM_PARACHUTE) from a boolean into a configurable failsafe parameter. The in-flight action is now selectable (Return or Land). Users previously on `COM_PARACHUTE=1` (block arming) must update to `2` to retain that behaviour; set to `3` or higher to also enable the in-flight failsafe action. ([PX4-Autopilot#26918](https://github.com/PX4/PX4-Autopilot/pull/26918))
### Control
@@ -54,6 +53,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
### Safety
- Rotary-wing vehicles now support uncommanded altitude loss detection: if the vehicle descends more than [FD_ALT_LOSS](../advanced_config/parameter_reference.md#FD_ALT_LOSS) meters below its setpoint in altitude-controlled flight, flight termination (and parachute deployment) is triggered. See [Altitude Loss Trigger](../config/safety.md#altitude-loss-trigger). ([PX4-Autopilot#26837](https://github.com/PX4/PX4-Autopilot/pull/26837))
- [Parachute health failsafe](../peripherals/parachute.md): extended [COM_PARACHUTE](../advanced_config/parameter_reference.md#COM_PARACHUTE) from a boolean into a configurable in-flight failsafe action (Return or Land) parameter. The previously enabled value `COM_PARACHUTE=1` causes a warning like before. ([PX4-Autopilot#26918](https://github.com/PX4/PX4-Autopilot/pull/26918))
- [GNSS check failsafe](../config/safety.md#gnss-check-failsafe): new failsafe that monitors the number of usable GNSS receivers with a 3D fix and their position consistency. The required number of receivers is set via [SYS_HAS_NUM_GNSS](../advanced_config/parameter_reference.md#SYS_HAS_NUM_GNSS) and the failsafe action via [COM_GNSSLOSS_ACT](../advanced_config/parameter_reference.md#COM_GNSSLOSS_ACT). ([PX4-Autopilot#26863](https://github.com/PX4/PX4-Autopilot/pull/26863))
### Estimation
@@ -38,64 +38,47 @@ using namespace time_literals;
void ParachuteChecks::checkAndReport(const Context &context, Report &reporter)
{
const int action = _param_com_parachute.get();
if (_param_com_parachute.get() < 1) { // COM_PARACHUTE 0 disables the check
return;
}
if (action > 0) {
reporter.failsafeFlags().parachute_unhealthy =
!context.status().parachute_system_present ||
!context.status().parachute_system_healthy;
reporter.failsafeFlags().parachute_unhealthy = !context.status().parachute_system_present || !context.status().parachute_system_healthy;
// Values >= 2 block arming; value 1 is warning-only
const bool warn_only = (action == 1);
const events::Log log_level = warn_only ? events::Log::Warning : events::Log::Error;
const NavModes affected_modes = warn_only ? NavModes::None : NavModes::All;
if (!context.status().parachute_system_present) {
/* EVENT
* @description
* No MAVLink parachute heartbeat detected. Check connection, power, configuration.
*
* <profile name="dev">
* Configured by <param>COM_PARACHUTE</param>
* </profile>
*/
reporter.healthFailure(NavModes::All, health_component_t::parachute, events::ID("check_parachute_missing"),
events::Log::Error, "Parachute system missing");
if (!context.status().parachute_system_present) {
/* EVENT
* @description
* No MAVLink parachute heartbeat detected. Check connection, power, configuration.
*
* <profile name="dev">
* Configured by <param>COM_PARACHUTE</param>
* </profile>
*/
reporter.healthFailure(affected_modes, health_component_t::parachute, events::ID("check_parachute_missing"),
log_level, "Parachute system missing");
if (reporter.mavlink_log_pub()) {
if (warn_only) {
mavlink_log_warning(reporter.mavlink_log_pub(), "Parachute system missing");
} else {
mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: Parachute system missing");
}
}
} else if (!context.status().parachute_system_healthy) {
/* EVENT
* @description
* MAVLink parachute system reports unhealthy status.
*
* <profile name="dev">
* Configured by <param>COM_PARACHUTE</param>
* </profile>
*/
reporter.healthFailure(affected_modes, health_component_t::parachute, events::ID("check_parachute_unhealthy"),
log_level, "Parachute system not ready");
if (reporter.mavlink_log_pub()) {
if (warn_only) {
mavlink_log_warning(reporter.mavlink_log_pub(), "Parachute system not ready");
} else {
mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: Parachute system not ready");
}
}
if (reporter.mavlink_log_pub()) {
mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: Parachute system missing");
}
if (context.status().parachute_system_present) {
reporter.setIsPresent(health_component_t::parachute);
} else if (!context.status().parachute_system_healthy) {
/* EVENT
* @description
* MAVLink parachute system reports unhealthy status.
*
* <profile name="dev">
* Configured by <param>COM_PARACHUTE</param>
* </profile>
*/
reporter.healthFailure(NavModes::All, health_component_t::parachute, events::ID("check_parachute_unhealthy"),
events::Log::Error, "Parachute system not ready");
if (reporter.mavlink_log_pub()) {
mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: Parachute system not ready");
}
}
if (context.status().parachute_system_present) {
reporter.setIsPresent(health_component_t::parachute);
}
}
+5 -17
View File
@@ -89,8 +89,6 @@ parameters:
7: 'Prio: RC > MAVL 2 > MAVL 1'
8: 'Prio: MAVL 2 > MAVL 1 > RC'
default: 3
min: 0
max: 8
COM_DISARM_LAND:
description:
short: Time-out for auto disarm after landing
@@ -411,8 +409,6 @@ parameters:
5: Terminate
6: Disarm
default: 0
min: 0
max: 6
NAV_RCL_ACT:
description:
short: Set manual control loss failsafe mode
@@ -427,8 +423,6 @@ parameters:
5: Terminate
6: Disarm
default: 2
min: 1
max: 6
COM_RCL_EXCEPT:
description:
short: Manual control loss exceptions
@@ -476,24 +470,18 @@ parameters:
3: Return mode
4: Terminate
default: 0
min: 0
max: 4
COM_PARACHUTE:
description:
short: Parachute system monitoring and failsafe action
short: Parachute requirement and failsafe
long: |-
Configures whether a MAVLink parachute system is monitored and what action is
taken when it reports missing or unhealthy status.
From Error onwards the check also blocks arming.
Require a MAVLink parachute system for arming and the failsafe action when missing or unhealthy.
type: enum
values:
0: Disabled
1: Warning only
2: Error (blocks arming)
3: Return
4: Land
1: Warning
2: Return
3: Land
default: 0
increment: 1
COM_ARM_CHK_ESCS:
description:
short: Enable checks on ESCs that report telemetry
+1 -2
View File
@@ -414,7 +414,6 @@ FailsafeBase::ActionOptions Failsafe::fromParachuteActParam(int param_value)
break;
case parachute_unhealthy_failsafe_mode::Warning:
case parachute_unhealthy_failsafe_mode::Error:
options.action = Action::Warn;
options.clear_condition = ClearCondition::WhenConditionClears;
break;
@@ -628,7 +627,7 @@ void Failsafe::checkStateAndMode(const hrt_abstime &time_us, const State &state,
}
// Parachute system health failsafe
CHECK_FAILSAFE(status_flags, parachute_unhealthy, ActionOptions(fromParachuteActParam(_param_com_parachute_act.get())));
CHECK_FAILSAFE(status_flags, parachute_unhealthy, ActionOptions(fromParachuteActParam(_param_com_parachute.get())));
// Remote ID (Open Drone ID) loss failsafe
if (state.armed && _param_com_arm_odid.get() >= int32_t(open_drone_id_failsafe_mode::Return_mode)) {
+3 -4
View File
@@ -162,9 +162,8 @@ private:
enum class parachute_unhealthy_failsafe_mode : int32_t {
Disabled = 0,
Warning = 1,
Error = 2,
Return = 3,
Land = 4,
Return = 2,
Land = 3,
};
enum class gps_redundancy_failsafe_mode : int32_t {
@@ -228,7 +227,7 @@ private:
(ParamInt<px4::params::COM_FLTT_LOW_ACT>) _param_com_fltt_low_act,
(ParamInt<px4::params::COM_POS_LOW_ACT>) _param_com_pos_low_act,
(ParamInt<px4::params::COM_ARM_ODID>) _param_com_arm_odid,
(ParamInt<px4::params::COM_PARACHUTE>) _param_com_parachute_act,
(ParamInt<px4::params::COM_PARACHUTE>) _param_com_parachute,
(ParamInt<px4::params::COM_GNSSLOSS_ACT>) _param_com_gnssloss_act
);