Skip to content
Open
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
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,10 @@ void ParachuteChecks::checkAndReport(const Context &context, Report &reporter)
!context.status().parachute_system_present ||
!context.status().parachute_system_healthy;

const bool warn_only = (_param_com_para_act.get() == 0);
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
Expand All @@ -55,11 +59,16 @@ void ParachuteChecks::checkAndReport(const Context &context, Report &reporter)
* 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");
reporter.healthFailure(affected_modes, health_component_t::parachute, events::ID("check_parachute_missing"),
log_level, "Parachute system missing");

if (reporter.mavlink_log_pub()) {
mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: Parachute system missing");
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) {
Expand All @@ -72,11 +81,16 @@ void ParachuteChecks::checkAndReport(const Context &context, Report &reporter)
* 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");
reporter.healthFailure(affected_modes, health_component_t::parachute, events::ID("check_parachute_unhealthy"),
log_level, "Parachute system not ready");

if (reporter.mavlink_log_pub()) {
mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: Parachute system not ready");
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");
}
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@ class ParachuteChecks : public HealthAndArmingCheckBase

private:
DEFINE_PARAMETERS_CUSTOM_PARENT(HealthAndArmingCheckBase,
(ParamBool<px4::params::COM_PARACHUTE>) _param_com_parachute
(ParamBool<px4::params::COM_PARACHUTE>) _param_com_parachute,
(ParamInt<px4::params::COM_PARA_ACT>) _param_com_para_act
)
};
13 changes: 13 additions & 0 deletions src/modules/commander/commander_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -513,6 +513,19 @@ parameters:
short: Require MAVLink parachute system to be present and healthy
type: boolean
default: 0
COM_PARA_ACT:
description:
short: Parachute system unhealthy failsafe action
long: |-
Action taken when the parachute system is enabled (COM_PARACHUTE=1) but reports
missing or unhealthy status during flight.
type: enum
values:
0: Warning
1: Land
2: Return
default: 2
increment: 1
COM_ARM_CHK_ESCS:
description:
short: Enable checks on ESCs that report telemetry
Expand Down
26 changes: 25 additions & 1 deletion src/modules/commander/failsafe/failsafe.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -412,6 +412,30 @@ FailsafeBase::ActionOptions Failsafe::fromPosLowActParam(int param_value)
return options;
}

FailsafeBase::ActionOptions Failsafe::fromParachuteActParam(int param_value)
{
ActionOptions options{};
options.clear_condition = ClearCondition::OnModeChangeOrDisarm;

switch (parachute_unhealthy_failsafe_mode(param_value)) {
case parachute_unhealthy_failsafe_mode::Warning:
default:
options.action = Action::Warn;
options.clear_condition = ClearCondition::WhenConditionClears;
break;

case parachute_unhealthy_failsafe_mode::Land:
options.action = Action::Land;
break;

case parachute_unhealthy_failsafe_mode::Return:
options.action = Action::RTL;
break;
}

return options;
}

FailsafeBase::ActionOptions Failsafe::fromRemainingFlightTimeLowActParam(int param_value)
{
ActionOptions options{};
Expand Down Expand Up @@ -575,7 +599,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())));

// Battery low failsafe
// If battery was low and arming was allowed through COM_ARM_BAT_MIN, don't failsafe immediately for the current low battery warning state
Expand Down
10 changes: 9 additions & 1 deletion src/modules/commander/failsafe/failsafe.h
Original file line number Diff line number Diff line change
Expand Up @@ -157,6 +157,12 @@ class Failsafe : public FailsafeBase
Return_mode = 3
};

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

static ActionOptions fromNavDllOrRclActParam(int param_value);

static ActionOptions fromGfActParam(int param_value);
Expand All @@ -168,6 +174,7 @@ class Failsafe : public FailsafeBase
static ActionOptions fromHighWindLimitActParam(int param_value);
static ActionOptions fromPosLowActParam(int param_value);
static ActionOptions fromRemainingFlightTimeLowActParam(int param_value);
static ActionOptions fromParachuteActParam(int param_value);

static bool isFailsafeIgnored(uint8_t user_intended_mode, int32_t exception_mask_parameter);

Expand Down Expand Up @@ -209,7 +216,8 @@ class Failsafe : public FailsafeBase
(ParamInt<px4::params::COM_QC_ACT>) _param_com_qc_act,
(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_POS_LOW_ACT>) _param_com_pos_low_act,
(ParamInt<px4::params::COM_PARA_ACT>) _param_com_parachute_act
);

};
Loading