AP_BattMonitor_UAVCAN: update to use capacity_remaining_pct() as a bool

This commit is contained in:
Willian Galvani 2021-02-17 11:02:34 -03:00
parent 27dd354304
commit 2eed23dcd6
2 changed files with 7 additions and 6 deletions

View File

@ -146,16 +146,17 @@ void AP_BattMonitor_UAVCAN::read()
_has_temperature = (AP_HAL::millis() - _state.temperature_time) <= AP_BATT_MONITOR_TIMEOUT;
}
/// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
uint8_t AP_BattMonitor_UAVCAN::capacity_remaining_pct() const
/// capacity_remaining_pct - returns true if the percentage is valid and writes to percentage argument
bool AP_BattMonitor_UAVCAN::capacity_remaining_pct(uint8_t &percentage) const
{
if ((uint32_t(_params._options.get()) & uint32_t(AP_BattMonitor_Params::Options::Ignore_UAVCAN_SoC)) ||
_soc > 100) {
// a UAVCAN battery monitor may not be able to supply a state of charge. If it can't then
// the user can set the option to use current integration in the backend instead.
return AP_BattMonitor_Backend::capacity_remaining_pct();
return AP_BattMonitor_Backend::capacity_remaining_pct(percentage);
}
return _soc;
percentage = _soc;
return true;
}
#endif

View File

@ -24,8 +24,8 @@ public:
/// Read the battery voltage and current. Should be called at 10hz
void read() override;
/// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
uint8_t capacity_remaining_pct() const override;
/// capacity_remaining_pct - returns true if the percentage is valid and writes to percentage argument
bool capacity_remaining_pct(uint8_t &percentage) const override;
bool has_temperature() const override { return _has_temperature; }