Browse Source

AP_BattMonitor_Backend: change capacity_remaining_pct() to a bool

gps-1.3.1
Willian Galvani 5 years ago committed by Andrew Tridgell
parent
commit
207723319b
  1. 15
      libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp
  2. 4
      libraries/AP_BattMonitor/AP_BattMonitor_Backend.h

15
libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp

@ -30,15 +30,16 @@ AP_BattMonitor_Backend::AP_BattMonitor_Backend(AP_BattMonitor &mon, AP_BattMonit @@ -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)
uint8_t AP_BattMonitor_Backend::capacity_remaining_pct() const
/// capacity_remaining_pct - returns true if the battery % is available and writes to the percentage argument
bool AP_BattMonitor_Backend::capacity_remaining_pct(uint8_t &percentage) const
{
float mah_remaining = _params._pack_capacity - _state.consumed_mah;
if ( _params._pack_capacity > 10 ) { // a very very small battery
return MIN(MAX((100 * (mah_remaining) / _params._pack_capacity), 0), UINT8_MAX);
} else {
return 0;
// 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) {
return false;
}
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

4
libraries/AP_BattMonitor/AP_BattMonitor_Backend.h

@ -46,8 +46,8 @@ public: @@ -46,8 +46,8 @@ public:
// returns true if battery monitor provides temperature
virtual bool has_temperature() const { return false; }
/// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
virtual uint8_t capacity_remaining_pct() const;
/// capacity_remaining_pct - returns true if the percentage is valid and writes to percentage argument
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
virtual bool get_cycle_count(uint16_t &cycles) const { return false; }

Loading…
Cancel
Save