Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 10 additions & 0 deletions docs/en/config/safety.md
Original file line number Diff line number Diff line change
Expand Up @@ -280,6 +280,16 @@ The failsafe action and arming behaviour are both configured by the `COM_ARM_ODI
| ----------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| <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 (prevents arming), `3`: Return, `4`: Land, `5`: Terminate.<br><br>On failsafe:<br>- `Error`, `Return`, `Land` and `Terminate` prevent arming.<br>- `Return`, `Land` and `Terminate` start the associated action/mode when airborne. |

## Parachute Health Failsafe

<Badge type="tip" text="PX4 v1.18" />

The parachute health failsafe is triggered when a [MAVLink parachute](../peripherals/parachute.md) system is missing or unhealthy while the vehicle is armed or airborne.
Comment thread
hamishwillee marked this conversation as resolved.

| Parameter | Description |
| -------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ |
| <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

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.
Expand Down
6 changes: 4 additions & 2 deletions docs/en/peripherals/parachute.md
Original file line number Diff line number Diff line change
Expand Up @@ -74,11 +74,13 @@ 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=1](../advanced_config/parameter_reference.md#COM_PARACHUTE).
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).

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:

- `SYS_STATUS.onboard_control_sensors_present_extended`: MAVLink parachute present (based on heartbeat detection).
- `SYS_STATUS.onboard_control_sensors_enabled_extended`: ?
- `SYS_STATUS.onboard_control_sensors_enabled_extended`: MAVLink parachute is enabled ([`COM_PARACHUTE > 0`](../advanced_config/parameter_reference.md#COM_PARACHUTE)).
- `SYS_STATUS.onboard_control_sensors_health_extended`: MAVLink parachute healthy (based on heartbeat detection).

A MAVLink parachute is required to emit a [HEARTBEAT](https://mavlink.io/en/messages/common.html#HEARTBEAT) with `HEARTBEAT.type` of [MAV_TYPE_PARACHUTE](https://mavlink.io/en/messages/common.html#MAV_TYPE_PARACHUTE).
Expand Down
1 change: 1 addition & 0 deletions docs/en/releases/main.md
Original file line number Diff line number Diff line change
Expand Up @@ -53,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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,21 +38,19 @@ using namespace time_literals;

void ParachuteChecks::checkAndReport(const Context &context, Report &reporter)
{
if (!_param_com_parachute.get()) {
if (_param_com_parachute.get() < 1) { // COM_PARACHUTE 0 disables the check
return;
}

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;

if (!context.status().parachute_system_present) {
/* EVENT
* @description
* No MAVLink parachute heartbeat detected. Check connection, power, configuration.
*
* <profile name="dev">
* Enabled by <param>COM_PARACHUTE</param>
* Configured by <param>COM_PARACHUTE</param>
* </profile>
*/
reporter.healthFailure(NavModes::All, health_component_t::parachute, events::ID("check_parachute_missing"),
Expand All @@ -69,7 +67,7 @@ void ParachuteChecks::checkAndReport(const Context &context, Report &reporter)
* MAVLink parachute system reports unhealthy status.
*
* <profile name="dev">
* Enabled by <param>COM_PARACHUTE</param>
* Configured by <param>COM_PARACHUTE</param>
* </profile>
*/
reporter.healthFailure(NavModes::All, health_component_t::parachute, events::ID("check_parachute_unhealthy"),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,6 @@ class ParachuteChecks : public HealthAndArmingCheckBase

private:
DEFINE_PARAMETERS_CUSTOM_PARENT(HealthAndArmingCheckBase,
(ParamBool<px4::params::COM_PARACHUTE>) _param_com_parachute
(ParamInt<px4::params::COM_PARACHUTE>) _param_com_parachute
)
};
19 changes: 9 additions & 10 deletions src/modules/commander/commander_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand All @@ -427,8 +423,6 @@ parameters:
5: Terminate
6: Disarm
default: 2
min: 1
max: 6
COM_RCL_EXCEPT:
description:
short: Manual control loss exceptions
Expand Down Expand Up @@ -476,12 +470,17 @@ parameters:
3: Return mode
4: Terminate
default: 0
min: 0
max: 4
COM_PARACHUTE:
description:
short: Require MAVLink parachute system to be present and healthy
type: boolean
short: Parachute requirement and failsafe
long: |-
Require a MAVLink parachute system for arming and the failsafe action when missing or unhealthy.
type: enum
values:
0: Disabled
1: Warning
2: Return
3: Land
default: 0
COM_ARM_CHK_ESCS:
description:
Expand Down
31 changes: 30 additions & 1 deletion src/modules/commander/failsafe/failsafe.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -403,6 +403,35 @@ FailsafeBase::ActionOptions Failsafe::fromGnssLossActParam(int param_value)
return options;
}

FailsafeBase::ActionOptions Failsafe::fromParachuteActParam(int param_value)
{
ActionOptions options{};

switch (parachute_unhealthy_failsafe_mode(param_value)) {
case parachute_unhealthy_failsafe_mode::Disabled:
default:
options.action = Action::None;
break;

case parachute_unhealthy_failsafe_mode::Warning:
options.action = Action::Warn;
options.clear_condition = ClearCondition::WhenConditionClears;
break;

case parachute_unhealthy_failsafe_mode::Return:
options.action = Action::RTL;
options.clear_condition = ClearCondition::OnModeChangeOrDisarm;
break;

case parachute_unhealthy_failsafe_mode::Land:
options.action = Action::Land;
options.clear_condition = ClearCondition::OnModeChangeOrDisarm;
break;
}

return options;
}

FailsafeBase::ActionOptions Failsafe::fromRemainingFlightTimeLowActParam(int param_value)
{
ActionOptions options{};
Expand Down Expand Up @@ -598,7 +627,7 @@ void Failsafe::checkStateAndMode(const hrt_abstime &time_us, const State &state,
}

// Parachute system health failsafe
CHECK_FAILSAFE(status_flags, parachute_unhealthy, Action::RTL);
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)) {
Expand Down
9 changes: 9 additions & 0 deletions src/modules/commander/failsafe/failsafe.h
Original file line number Diff line number Diff line change
Expand Up @@ -159,6 +159,13 @@ class Failsafe : public FailsafeBase
Terminate = 5,
};

enum class parachute_unhealthy_failsafe_mode : int32_t {
Disabled = 0,
Warning = 1,
Return = 2,
Land = 3,
};

enum class gps_redundancy_failsafe_mode : int32_t {
Warning = 0,
Return_mode = 1,
Expand All @@ -177,6 +184,7 @@ class Failsafe : public FailsafeBase
static ActionOptions fromPosLowActParam(int param_value);
static ActionOptions fromRemainingFlightTimeLowActParam(int param_value);
static ActionOptions fromOdidFailActParam(int param_value);
static ActionOptions fromParachuteActParam(int param_value);
static ActionOptions fromGnssLossActParam(int param_value);

static bool isFailsafeIgnored(uint8_t user_intended_mode, int32_t exception_mask_parameter);
Expand Down Expand Up @@ -219,6 +227,7 @@ class Failsafe : public FailsafeBase
(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,
(ParamInt<px4::params::COM_GNSSLOSS_ACT>) _param_com_gnssloss_act
);

Expand Down
Loading