AP_BattMonitor: Fix nullptr deref when resetting a battery
This commit is contained in:
parent
d1dcfd91b5
commit
e5de148ad1
@ -77,7 +77,6 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = {
|
||||
//
|
||||
AP_BattMonitor::AP_BattMonitor(uint32_t log_battery_bit, battery_failsafe_handler_fn_t battery_failsafe_handler_fn, const int8_t *failsafe_priorities) :
|
||||
_log_battery_bit(log_battery_bit),
|
||||
_num_instances(0),
|
||||
_battery_failsafe_handler_fn(battery_failsafe_handler_fn),
|
||||
_failsafe_priorities(failsafe_priorities)
|
||||
{
|
||||
@ -557,11 +556,16 @@ void AP_BattMonitor::checkPoweringOff(void)
|
||||
*/
|
||||
bool AP_BattMonitor::reset_remaining(uint16_t battery_mask, float percentage)
|
||||
{
|
||||
static_assert(AP_BATT_MONITOR_MAX_INSTANCES <= 16, "More batteries are enabled then can be reset");
|
||||
bool ret = true;
|
||||
Failsafe highest_failsafe = Failsafe::None;
|
||||
for (uint8_t i = 0; i < _num_instances; i++) {
|
||||
if ((1U<<i) & battery_mask) {
|
||||
ret &= drivers[i]->reset_remaining(percentage);
|
||||
if (drivers[i] != nullptr) {
|
||||
ret &= drivers[i]->reset_remaining(percentage);
|
||||
} else {
|
||||
ret = false;
|
||||
}
|
||||
}
|
||||
if (state[i].failsafe > highest_failsafe) {
|
||||
highest_failsafe = state[i].failsafe;
|
||||
|
Loading…
Reference in New Issue
Block a user