AP_BattMonitor: reset failsafe flags when we reset battery remaining
This commit is contained in:
parent
f28df4dff1
commit
88111ef81a
@ -501,10 +501,22 @@ void AP_BattMonitor::checkPoweringOff(void)
|
||||
bool AP_BattMonitor::reset_remaining(uint16_t battery_mask, float percentage)
|
||||
{
|
||||
bool ret = true;
|
||||
BatteryFailsafe highest_failsafe = BatteryFailsafe_None;
|
||||
for (uint8_t i = 0; i < _num_instances; i++) {
|
||||
if ((1U<<i) & battery_mask) {
|
||||
ret &= drivers[i]->reset_remaining(percentage);
|
||||
}
|
||||
if (state[i].failsafe > highest_failsafe) {
|
||||
highest_failsafe = state[i].failsafe;
|
||||
}
|
||||
}
|
||||
|
||||
// If all backends are not in failsafe then set overall failsafe state
|
||||
if (highest_failsafe == BatteryFailsafe_None) {
|
||||
_highest_failsafe_priority = INT8_MAX;
|
||||
_has_triggered_failsafe = false;
|
||||
// and reset notify flag
|
||||
AP_Notify::flags.failsafe_battery = false;
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
@ -232,5 +232,8 @@ bool AP_BattMonitor_Backend::reset_remaining(float percentage)
|
||||
// full charge
|
||||
_state.consumed_wh = _state.consumed_mah * 1000 * _state.voltage;
|
||||
|
||||
// reset failsafe state for this backend
|
||||
_state.failsafe = update_failsafes();
|
||||
|
||||
return true;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user