AP_BattMonitor: cope with NaN in consumed_mah

This commit is contained in:
Andrew Tridgell 2023-08-25 19:50:39 +10:00
parent bc825fb4c1
commit 65537bdaca
1 changed files with 5 additions and 1 deletions

View File

@ -566,7 +566,11 @@ bool AP_BattMonitor::current_amps(float &current, uint8_t instance) const {
/// consumed_mah - returns total current drawn since start-up in milliampere.hours
bool AP_BattMonitor::consumed_mah(float &mah, const uint8_t instance) const {
if ((instance < _num_instances) && (drivers[instance] != nullptr) && drivers[instance]->has_current()) {
mah = state[instance].consumed_mah;
const float consumed_mah = state[instance].consumed_mah;
if (isnan(consumed_mah)) {
return false;
}
mah = consumed_mah;
return true;
} else {
return false;