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