fix(commander): combine all battery failsafe configuration into COM_LOW_BAT_ACT to make the options very clear for the user

This commit is contained in:
Matthias Grob
2026-04-02 17:57:57 +02:00
parent 197a1a6214
commit f6bb708cfc
6 changed files with 56 additions and 80 deletions
@@ -300,7 +300,6 @@
1 1 COM_FLTMODE4 11 6
1 1 COM_FLTMODE5 -1 6
1 1 COM_FLTMODE6 8 6
1 1 COM_FLTT_LOW_ACT 3 6
1 1 COM_FLT_TIME_MAX -1 6
1 1 COM_FORCE_SAFETY 0 6
1 1 COM_HLDL_LOSS_T 120 6
+9 -17
View File
@@ -77,37 +77,29 @@ QGC allows users to set some aspects of the landing behaviour, such as the time
### Battery level failsafe
The low battery failsafe is triggered when the battery capacity drops below battery failafe level values.
The low battery failsafe is triggered when the battery capacity drops below battery failsafe level values.
You can configure both the levels and the failsafe actions at each level in QGroundControl.
![Safety - Battery (QGC)](../../assets/qgc/setup/safety/safety_battery.png)
The most common configuration is to set the values and action as above (with `Warn > Failsafe > Emergency`), and to set the [Failsafe Action](#COM_LOW_BAT_ACT) to warn at "warn level", trigger Return mode at "Failsafe level", and land immediately at "Emergency level".
The most common configuration is to set the values and action as above (with `Warn > Failsafe > Emergency`), and to set the [Failsafe Action](#COM_LOW_BAT_ACT) to warn at "warn level", trigger Return mode at "Failsafe level", and land immediately at "Emergency level". The same parameter also controls the bingo fuel failsafe, which triggers Return mode when the estimated remaining flight time drops below what is needed to return safely (requires `BATn_CAPACITY` to be set).
The settings and underlying parameters are shown below.
| Setting | Parameter | Description |
| --------------------------------------------------- | ---------------------------------------------------------------------------- | ------------------------------------------------------------------------------------- |
| <a id="COM_LOW_BAT_ACT"></a>Failsafe Action | [COM_LOW_BAT_ACT](../advanced_config/parameter_reference.md#COM_LOW_BAT_ACT) | Warn, Return, or Land based when capacity drops below the trigger levels. |
| <a id="COM_LOW_BAT_ACT"></a>Failsafe Action | [COM_LOW_BAT_ACT](../advanced_config/parameter_reference.md#COM_LOW_BAT_ACT) | Action when battery capacity drops below the trigger levels, and for bingo fuel (flight time drops below return flight time). |
| <a id="BAT_LOW_THR"></a>Battery Warn Level | [BAT_LOW_THR](../advanced_config/parameter_reference.md#BAT_LOW_THR) | Percentage capacity for warnings (or other actions). |
| <a id="BAT_CRIT_THR"></a>Battery Failsafe Level | [BAT_CRIT_THR](../advanced_config/parameter_reference.md#BAT_CRIT_THR) | Percentage capacity for Return action (or other actions if a single action selected). |
| <a id="BAT_EMERGEN_THR"></a>Battery Emergency Level | [BAT_EMERGEN_THR](../advanced_config/parameter_reference.md#BAT_EMERGEN_THR) | Percentage capacity for triggering Land (immediately) action. |
| <a id="COM_ARM_BAT_MIN"></a>Minimum armable state of charge | [COM_ARM_BAT_MIN](../advanced_config/parameter_reference.md#COM_ARM_BAT_MIN) | Prevents arming if the battery state of charge is below the specified value. |
### Flight Time Failsafes
### Maximum Flight Time Failsafe
There are several other "battery related" failsafe mechanisms that may be configured using parameters:
The maximum flight time failsafe ([COM_FLT_TIME_MAX](#COM_FLT_TIME_MAX)) allows you to set a maximum flight time after takeoff, at which the vehicle will automatically enter return mode (it will also "warn" at 90% of this time). This is to comply with certain regulations where the mission has to be aborted if it takes longer than a certain amount of time. The feature is disabled by default.
- The "remaining flight time for safe return" failsafe ([COM_FLTT_LOW_ACT](#COM_FLTT_LOW_ACT)) is engaged when PX4 estimates that the vehicle has just enough battery remaining for a return mode landing.
You can configure this to ignore the failsafe, warn, or engage Return mode.
- The "maximum flight time failsafe" ([COM_FLT_TIME_MAX](#COM_FLT_TIME_MAX)) allows you to set a maximum flight time after takeoff, at which the vehicle will automatically enter return mode (it will also "warn" at 90% of this time). This is like a "hard coded" estimate of the total flight time in a battery. The feature is disabled by default.
- The "minimum battery" for arming parameter ([COM_ARM_BAT_MIN](#COM_ARM_BAT_MIN)) prevents arming in the first place if the battery level is below the specified value.
The settings and underlying parameters are shown below.
| Setting | Parameter | Description |
| -------------------------------------------------------------------- | ------------------------------------------------------------------------------ | ------------------------------------------------------------------------------------------------------------------------------- |
| <a id="COM_FLTT_LOW_ACT"></a> Low flight time for safe return action | [COM_FLTT_LOW_ACT](../advanced_config/parameter_reference.md#COM_FLTT_LOW_ACT) | Action when return mode can only just reach safety with remaining battery. `0`: None (default), `1`: Warning, `3`: Return mode. |
| <a id="COM_FLT_TIME_MAX"></a> Maximum flight time failsafe level | [COM_FLT_TIME_MAX](../advanced_config/parameter_reference.md#COM_FLT_TIME_MAX) | Maximum allowed flight time before Return mode will be engaged, in seconds. `-1`: Disabled (default). |
| Setting | Parameter | Description |
| ---------------------------------------------------------------- | ------------------------------------------------------------------------------ | -------------------------------------------------------------------------------------- |
| <a id="COM_FLT_TIME_MAX"></a> Maximum flight time failsafe level | [COM_FLT_TIME_MAX](../advanced_config/parameter_reference.md#COM_FLT_TIME_MAX) | Maximum allowed flight time before Return mode will be engaged, in seconds. `-1`: Disabled (default). |
## Manual Control Loss Failsafe
+7 -17
View File
@@ -153,15 +153,18 @@ parameters:
default: 1
COM_LOW_BAT_ACT:
description:
short: Battery failsafe mode
short: Battery & bingo fuel failsafe
long: |-
Action the system takes at critical battery. See also BAT_CRIT_THR and BAT_EMERGEN_THR
for definition of battery states.
Action the system takes when battery gets low on charge. See also BAT_CRIT_THR and BAT_EMERGEN_THR
for definition of battery levels.
Bingo fuel - RTL when estimated remaining flight time is low, only works when BATn_CAPACITY is set.
type: enum
values:
0: Warning
2: Land mode
3: Return at critical level, land at emergency level
3: Bingo fuel, Critical RTL , Emergency land
4: Critical RTL , Emergency land
5: Warning, no bingo fuel
default: 0
COM_FAIL_ACT_T:
description:
@@ -792,19 +795,6 @@ parameters:
decimal: 1
increment: 0.1
unit: m/s
COM_FLTT_LOW_ACT:
description:
short: Remaining flight time low failsafe
long: |-
Action the system takes when the remaining flight time is below
the estimated time it takes to reach the RTL destination.
type: enum
values:
0: None
1: Warning
3: Return
default: 0
increment: 1
COM_MODE_ARM_CHK:
description:
short: Allow external mode registration while armed
+33 -37
View File
@@ -187,6 +187,8 @@ FailsafeBase::ActionOptions Failsafe::fromActuatorFailureActParam(int param_valu
return options;
}
static constexpr uint8_t BATTERY_WARNING_BINGO_FUEL = UINT8_MAX; // "battery level" to handle bingo fuel
FailsafeBase::ActionOptions Failsafe::fromBatteryWarningActParam(int param_value, uint8_t battery_warning)
{
ActionOptions options{};
@@ -209,6 +211,7 @@ FailsafeBase::ActionOptions Failsafe::fromBatteryWarningActParam(int param_value
switch ((LowBatteryAction)param_value) {
case LowBatteryAction::Return:
case LowBatteryAction::ReturnOrLand:
case LowBatteryAction::ReturnOrLandNoBingo:
options.action = Action::RTL;
break;
@@ -217,6 +220,7 @@ FailsafeBase::ActionOptions Failsafe::fromBatteryWarningActParam(int param_value
break;
case LowBatteryAction::Warning:
case LowBatteryAction::WarningNoBingo:
options.action = Action::Warn;
break;
}
@@ -232,17 +236,41 @@ FailsafeBase::ActionOptions Failsafe::fromBatteryWarningActParam(int param_value
options.action = Action::RTL;
break;
case LowBatteryAction::ReturnOrLand:
case LowBatteryAction::Land:
case LowBatteryAction::ReturnOrLand:
case LowBatteryAction::ReturnOrLandNoBingo:
options.action = Action::Land;
break;
case LowBatteryAction::Warning:
case LowBatteryAction::WarningNoBingo:
options.action = Action::Warn;
break;
}
break;
case BATTERY_WARNING_BINGO_FUEL:
options.action = Action::Warn;
options.cause = Cause::RemainingFlightTimeLow;
switch ((LowBatteryAction)param_value) {
case LowBatteryAction::Return:
case LowBatteryAction::ReturnOrLand:
options.action = Action::RTL;
options.clear_condition = ClearCondition::OnModeChangeOrDisarm;
break;
case LowBatteryAction::Warning:
case LowBatteryAction::Land:
options.action = Action::Warn;
break;
case LowBatteryAction::ReturnOrLandNoBingo:
case LowBatteryAction::WarningNoBingo:
options.action = Action::None;
break;
}
}
return options;
@@ -412,36 +440,6 @@ FailsafeBase::ActionOptions Failsafe::fromPosLowActParam(int param_value)
return options;
}
FailsafeBase::ActionOptions Failsafe::fromRemainingFlightTimeLowActParam(int param_value)
{
ActionOptions options{};
options.allow_user_takeover = UserTakeoverAllowed::Auto;
options.cause = Cause::RemainingFlightTimeLow;
switch (command_after_remaining_flight_time_low(param_value)) {
case command_after_remaining_flight_time_low::None:
options.action = Action::None;
break;
case command_after_remaining_flight_time_low::Warning:
options.action = Action::Warn;
break;
case command_after_remaining_flight_time_low::Return_mode:
options.action = Action::RTL;
options.clear_condition = ClearCondition::OnModeChangeOrDisarm;
break;
default:
options.action = Action::None;
break;
}
return options;
}
bool Failsafe::isFailsafeIgnored(uint8_t user_intended_mode, int32_t exception_mask_parameter)
{
switch (user_intended_mode) {
@@ -561,10 +559,6 @@ void Failsafe::checkStateAndMode(const hrt_abstime &time_us, const State &state,
CHECK_FAILSAFE(status_flags, geofence_breached, fromGfActParam(_param_gf_action.get()).cannotBeDeferred());
// Battery flight time remaining failsafe
CHECK_FAILSAFE(status_flags, battery_low_remaining_time,
ActionOptions(fromRemainingFlightTimeLowActParam(_param_com_fltt_low_act.get())));
if ((_armed_time != 0)
&& (time_us < _armed_time + static_cast<hrt_abstime>(_param_com_spoolup_time.get() * 1_s))
) {
@@ -580,8 +574,7 @@ void Failsafe::checkStateAndMode(const hrt_abstime &time_us, const State &state,
// 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
const bool warning_worse_than_at_arming = (status_flags.battery_warning > _battery_warning_at_arming);
const int32_t low_battery_action = warning_worse_than_at_arming ?
_param_com_low_bat_act.get() : (int32_t)LowBatteryAction::Warning;
const int32_t low_battery_action = warning_worse_than_at_arming ? _param_com_low_bat_act.get() : (int32_t)LowBatteryAction::Warning;
switch (status_flags.battery_warning) {
case battery_status_s::WARNING_LOW:
@@ -605,6 +598,9 @@ void Failsafe::checkStateAndMode(const hrt_abstime &time_us, const State &state,
break;
}
// Battery flight time remaining failsafe
CHECK_FAILSAFE(status_flags, battery_low_remaining_time,
ActionOptions(fromBatteryWarningActParam(_param_com_low_bat_act.get(), BATTERY_WARNING_BINGO_FUEL)));
// Handle fails during spoolup just after arming
if ((_armed_time != 0)
+6 -6
View File
@@ -63,10 +63,12 @@ private:
// COM_LOW_BAT_ACT parameter values
enum class LowBatteryAction : int32_t {
Warning = 0, // Warning
Return = 1, // Return mode (deprecated)
Land = 2, // Land mode
ReturnOrLand = 3 // Return mode at critically low level, Land mode at current position if reaching dangerously low levels
Warning = 0,
Return = 1, // Return mode (deprecated)
Land = 2, // Land mode
ReturnOrLand = 3, // Return mode at critically low level, Land mode at current position if reaching dangerously low levels
ReturnOrLandNoBingo = 4, // Same as above but without bingo fuel
WarningNoBingo = 5 // Warning only, bingo fuel silent
};
enum class offboard_loss_failsafe_mode : int32_t {
@@ -167,7 +169,6 @@ private:
static Action fromOffboardLossActParam(int param_value, uint8_t &user_intended_mode);
static ActionOptions fromHighWindLimitActParam(int param_value);
static ActionOptions fromPosLowActParam(int param_value);
static ActionOptions fromRemainingFlightTimeLowActParam(int param_value);
static bool isFailsafeIgnored(uint8_t user_intended_mode, int32_t exception_mask_parameter);
@@ -208,7 +209,6 @@ private:
(ParamInt<px4::params::COM_OBL_RC_ACT>) _param_com_obl_rc_act,
(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
);
+1 -2
View File
@@ -298,8 +298,7 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action
#endif /* EMSCRIPTEN_BUILD */
}
bool FailsafeBase::checkFailsafe(int caller_id, bool last_state_failure, bool cur_state_failure,
const ActionOptions &options)
bool FailsafeBase::checkFailsafe(int caller_id, bool last_state_failure, bool cur_state_failure, const ActionOptions &options)
{
if (cur_state_failure) {
// Invalid state: find or add action