mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_BattMonitor: capacity_remaining_pct add checks for healthy status and has_current
This commit is contained in:
parent
f298ea406e
commit
ca568953d9
@ -30,13 +30,20 @@ AP_BattMonitor_Backend::AP_BattMonitor_Backend(AP_BattMonitor &mon, AP_BattMonit
|
|||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
/// capacity_remaining_pct - returns true if the battery % is available and writes to the percentage argument
|
// capacity_remaining_pct - returns true if the battery % is available and writes to the percentage argument
|
||||||
|
// return false if the battery is unhealthy, does not have current monitoring, or the pack_capacity is too small
|
||||||
bool AP_BattMonitor_Backend::capacity_remaining_pct(uint8_t &percentage) const
|
bool AP_BattMonitor_Backend::capacity_remaining_pct(uint8_t &percentage) const
|
||||||
{
|
{
|
||||||
// we consider anything under 10 mAh as being an invalid capacity and so will be our measurement of remaining capacity
|
// 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) {
|
if ( _params._pack_capacity <= 10) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// the monitor must have current readings in order to estimate consumed_mah and be healthy
|
||||||
|
if (!has_current() || !_state.healthy) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
const float mah_remaining = _params._pack_capacity - _state.consumed_mah;
|
const float mah_remaining = _params._pack_capacity - _state.consumed_mah;
|
||||||
percentage = constrain_float(100 * mah_remaining / _params._pack_capacity, 0, UINT8_MAX);
|
percentage = constrain_float(100 * mah_remaining / _params._pack_capacity, 0, UINT8_MAX);
|
||||||
return true;
|
return true;
|
||||||
|
@ -46,7 +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 true if the percentage is valid and writes to percentage argument
|
// capacity_remaining_pct - returns true if the battery % is available and writes to the percentage argument
|
||||||
|
// returns false if the battery is unhealthy, does not have current monitoring, or the pack_capacity is too small
|
||||||
virtual bool capacity_remaining_pct(uint8_t &percentage) const WARN_IF_UNUSED;
|
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
|
||||||
|
@ -155,6 +155,12 @@ bool AP_BattMonitor_UAVCAN::capacity_remaining_pct(uint8_t &percentage) const
|
|||||||
// the user can set the option to use current integration in the backend instead.
|
// the user can set the option to use current integration in the backend instead.
|
||||||
return AP_BattMonitor_Backend::capacity_remaining_pct(percentage);
|
return AP_BattMonitor_Backend::capacity_remaining_pct(percentage);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// the monitor must have current readings in order to estimate consumed_mah and be healthy
|
||||||
|
if (!has_current() || !_state.healthy) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
percentage = _soc;
|
percentage = _soc;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user