mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 22:18:29 -04:00
AP_BattMonitor_Backend: change capacity_remaining_pct() to a bool
This commit is contained in:
parent
d5130e1f0e
commit
206d047ab1
@ -30,15 +30,16 @@ AP_BattMonitor_Backend::AP_BattMonitor_Backend(AP_BattMonitor &mon, AP_BattMonit
|
|||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
/// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
|
/// capacity_remaining_pct - returns true if the battery % is available and writes to the percentage argument
|
||||||
uint8_t AP_BattMonitor_Backend::capacity_remaining_pct() const
|
bool AP_BattMonitor_Backend::capacity_remaining_pct(uint8_t &percentage) const
|
||||||
{
|
{
|
||||||
float mah_remaining = _params._pack_capacity - _state.consumed_mah;
|
// we consider anything under 10 mAh as being an invalid capacity and so will be our measurement of remaining capacity
|
||||||
if ( _params._pack_capacity > 10 ) { // a very very small battery
|
if ( _params._pack_capacity <= 10) {
|
||||||
return MIN(MAX((100 * (mah_remaining) / _params._pack_capacity), 0), UINT8_MAX);
|
return false;
|
||||||
} else {
|
|
||||||
return 0;
|
|
||||||
}
|
}
|
||||||
|
const float mah_remaining = _params._pack_capacity - _state.consumed_mah;
|
||||||
|
percentage = constrain_float(100 * mah_remaining / _params._pack_capacity, 0, UINT8_MAX);
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
// update battery resistance estimate
|
// update battery resistance estimate
|
||||||
|
@ -46,8 +46,8 @@ public:
|
|||||||
// returns true if battery monitor provides temperature
|
// returns true if battery monitor provides temperature
|
||||||
virtual bool has_temperature() const { return false; }
|
virtual bool has_temperature() const { return false; }
|
||||||
|
|
||||||
/// 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() const;
|
virtual bool capacity_remaining_pct(uint8_t &percentage) const WARN_IF_UNUSED;
|
||||||
|
|
||||||
// return true if cycle count can be provided and fills in cycles argument
|
// return true if cycle count can be provided and fills in cycles argument
|
||||||
virtual bool get_cycle_count(uint16_t &cycles) const { return false; }
|
virtual bool get_cycle_count(uint16_t &cycles) const { return false; }
|
||||||
|
Loading…
Reference in New Issue
Block a user