feat(commander): add COM_PARA_ACT to configure parachute unhealthy failsafe

Previously the parachute unhealthy failsafe was hardcoded to RTL.
This commit is contained in:
gguidone
2026-03-31 17:45:11 +02:00
parent a779925618
commit c19ea51396
5 changed files with 109 additions and 43 deletions
@@ -38,49 +38,64 @@ using namespace time_literals;
void ParachuteChecks::checkAndReport(const Context &context, Report &reporter)
{
if (!_param_com_parachute.get()) {
return;
}
const int action = _param_com_parachute.get();
reporter.failsafeFlags().parachute_unhealthy =
!context.status().parachute_system_present ||
!context.status().parachute_system_healthy;
if (action > 0) {
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>
* </profile>
*/
reporter.healthFailure(NavModes::All, health_component_t::parachute, events::ID("check_parachute_missing"),
events::Log::Error, "Parachute system missing");
// 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 (reporter.mavlink_log_pub()) {
mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: 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");
}
}
}
} else if (!context.status().parachute_system_healthy) {
/* EVENT
* @description
* MAVLink parachute system reports unhealthy status.
*
* <profile name="dev">
* Enabled 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);
}
}
if (context.status().parachute_system_present) {
reporter.setIsPresent(health_component_t::parachute);
}
}
@@ -45,6 +45,6 @@ public:
private:
DEFINE_PARAMETERS_CUSTOM_PARENT(HealthAndArmingCheckBase,
(ParamBool<px4::params::COM_PARACHUTE>) _param_com_parachute
(ParamInt<px4::params::COM_PARACHUTE>) _param_com_parachute
)
};
+13 -2
View File
@@ -510,9 +510,20 @@ parameters:
max: 4
COM_PARACHUTE:
description:
short: Require MAVLink parachute system to be present and healthy
type: boolean
short: Parachute system monitoring and failsafe action
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.
type: enum
values:
0: Disabled
1: Warning only
2: Error (blocks arming)
3: Return
4: Land
default: 0
increment: 1
COM_ARM_CHK_ESCS:
description:
short: Enable checks on ESCs that report telemetry
+31 -1
View File
@@ -412,6 +412,36 @@ FailsafeBase::ActionOptions Failsafe::fromPosLowActParam(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:
case parachute_unhealthy_failsafe_mode::Error:
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{};
@@ -607,7 +637,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_act.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)) {
+11 -1
View File
@@ -166,6 +166,14 @@ private:
Terminate = 5,
};
enum class parachute_unhealthy_failsafe_mode : int32_t {
Disabled = 0,
Warning = 1,
Error = 2,
Return = 3,
Land = 4,
};
static ActionOptions fromNavDllOrRclActParam(int param_value);
static ActionOptions fromGfActParam(int param_value);
@@ -178,6 +186,7 @@ private:
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 bool isFailsafeIgnored(uint8_t user_intended_mode, int32_t exception_mask_parameter);
@@ -220,7 +229,8 @@ private:
(ParamInt<px4::params::COM_WIND_MAX_ACT>) _param_com_wind_max_act,
(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_ARM_ODID>) _param_com_arm_odid,
(ParamInt<px4::params::COM_PARACHUTE>) _param_com_parachute_act
);
};