mirror of https://github.com/ArduPilot/ardupilot
AP_BattMonitor: change capacity_remaining_pct() to a bool
This commit is contained in:
parent
d00b9e88c5
commit
d5130e1f0e
|
@ -376,14 +376,13 @@ bool AP_BattMonitor::consumed_wh(float &wh, const uint8_t instance) const {
|
|||
}
|
||||
}
|
||||
|
||||
/// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
|
||||
uint8_t AP_BattMonitor::capacity_remaining_pct(uint8_t instance) const
|
||||
/// capacity_remaining_pct - returns true if the percentage is valid and writes to percentage argument
|
||||
bool AP_BattMonitor::capacity_remaining_pct(uint8_t &percentage, uint8_t instance) const
|
||||
{
|
||||
if (instance < _num_instances && drivers[instance] != nullptr) {
|
||||
return drivers[instance]->capacity_remaining_pct();
|
||||
} else {
|
||||
return 0;
|
||||
return drivers[instance]->capacity_remaining_pct(percentage);
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
/// pack_capacity_mah - returns the capacity of the battery pack in mAh when the pack is full
|
||||
|
|
|
@ -161,9 +161,9 @@ public:
|
|||
/// consumed_wh - returns total energy drawn since start-up in watt.hours
|
||||
bool consumed_wh(float&wh, const uint8_t instance = AP_BATT_PRIMARY_INSTANCE) const WARN_IF_UNUSED;
|
||||
|
||||
/// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
|
||||
virtual uint8_t capacity_remaining_pct(uint8_t instance) const;
|
||||
uint8_t capacity_remaining_pct() const { return capacity_remaining_pct(AP_BATT_PRIMARY_INSTANCE); }
|
||||
/// capacity_remaining_pct - returns true if the percentage is valid and writes to percentage argument
|
||||
virtual bool capacity_remaining_pct(uint8_t &percentage, uint8_t instance) const WARN_IF_UNUSED;
|
||||
bool capacity_remaining_pct(uint8_t &percentage) const WARN_IF_UNUSED { return capacity_remaining_pct(percentage, AP_BATT_PRIMARY_INSTANCE); }
|
||||
|
||||
/// pack_capacity_mah - returns the capacity of the battery pack in mAh when the pack is full
|
||||
int32_t pack_capacity_mah(uint8_t instance) const;
|
||||
|
|
Loading…
Reference in New Issue