mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AP_BatteryMonitor: count mWh spent since powerup
This commit is contained in:
parent
0da8ff6b2e
commit
7383552ebc
@ -196,6 +196,17 @@ bool AP_BattMonitor::healthy(uint8_t instance) const {
|
||||
return instance < _num_instances && state[instance].healthy;
|
||||
}
|
||||
|
||||
/// has_consumed_energy - returns true if battery monitor instance provides consumed energy info
|
||||
bool AP_BattMonitor::has_consumed_energy(uint8_t instance) const
|
||||
{
|
||||
if (instance < _num_instances && drivers[instance] != nullptr && _params[instance].type() != AP_BattMonitor_Params::BattMonitor_TYPE_NONE) {
|
||||
return drivers[instance]->has_consumed_energy();
|
||||
}
|
||||
|
||||
// not monitoring current
|
||||
return false;
|
||||
}
|
||||
|
||||
/// has_current - returns true if battery monitor instance provides current info
|
||||
bool AP_BattMonitor::has_current(uint8_t instance) const
|
||||
{
|
||||
@ -247,6 +258,15 @@ float AP_BattMonitor::current_total_mah(uint8_t instance) const {
|
||||
}
|
||||
}
|
||||
|
||||
/// consumed_wh - returns energy consumed since start-up in watt-hours
|
||||
float AP_BattMonitor::consumed_wh(uint8_t instance) const {
|
||||
if (instance < _num_instances) {
|
||||
return state[instance].consumed_wh;
|
||||
} else {
|
||||
return 0.0f;
|
||||
}
|
||||
}
|
||||
|
||||
/// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
|
||||
uint8_t AP_BattMonitor::capacity_remaining_pct(uint8_t instance) const
|
||||
{
|
||||
|
@ -55,6 +55,7 @@ public:
|
||||
float voltage; // voltage in volts
|
||||
float current_amps; // current in amperes
|
||||
float current_total_mah; // total current draw since start-up
|
||||
float consumed_wh; // total energy consumed in Wh since start-up
|
||||
uint32_t last_time_micros; // time when voltage and current was last read
|
||||
uint32_t low_voltage_start_ms; // time when voltage dropped below the minimum
|
||||
float temperature; // battery temperature in celsius
|
||||
@ -77,6 +78,10 @@ public:
|
||||
bool healthy(uint8_t instance) const;
|
||||
bool healthy() const { return healthy(AP_BATT_PRIMARY_INSTANCE); }
|
||||
|
||||
/// has_consumed_energy - returns true if battery monitor instance provides consumed energy info
|
||||
bool has_consumed_energy(uint8_t instance) const;
|
||||
bool has_consumed_energy() const { return has_consumed_energy(AP_BATT_PRIMARY_INSTANCE); }
|
||||
|
||||
/// has_current - returns true if battery monitor instance provides current info
|
||||
bool has_current(uint8_t instance) const;
|
||||
bool has_current() const { return has_current(AP_BATT_PRIMARY_INSTANCE); }
|
||||
@ -98,6 +103,10 @@ public:
|
||||
float current_total_mah(uint8_t instance) const;
|
||||
float current_total_mah() const { return current_total_mah(AP_BATT_PRIMARY_INSTANCE); }
|
||||
|
||||
/// consumed_wh - returns total energy drawn since start-up in watt-hours
|
||||
float consumed_wh(uint8_t instance) const;
|
||||
float consumed_wh() const { return consumed_wh(AP_BATT_PRIMARY_INSTANCE); }
|
||||
|
||||
/// 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); }
|
||||
|
@ -44,7 +44,9 @@ AP_BattMonitor_Analog::read()
|
||||
// update total current drawn since startup
|
||||
if (_state.last_time_micros != 0 && dt < 2000000.0f) {
|
||||
// .0002778 is 1/3600 (conversion to hours)
|
||||
_state.current_total_mah += _state.current_amps * dt * 0.0000002778f;
|
||||
float mah = _state.current_amps * dt * 0.0000002778f;
|
||||
_state.current_total_mah += mah;
|
||||
_state.consumed_wh += 0.001f * mah * _state.voltage;
|
||||
}
|
||||
|
||||
// record time
|
||||
|
@ -115,6 +115,9 @@ public:
|
||||
/// Read the battery voltage and current. Should be called at 10hz
|
||||
void read();
|
||||
|
||||
/// returns true if battery monitor provides consumed energy info
|
||||
bool has_consumed_energy() const override { return has_current(); }
|
||||
|
||||
/// returns true if battery monitor provides current info
|
||||
bool has_current() const override;
|
||||
|
||||
|
@ -34,6 +34,9 @@ public:
|
||||
// read the latest battery voltage
|
||||
virtual void read() = 0;
|
||||
|
||||
/// returns true if battery monitor instance provides consumed energy info
|
||||
virtual bool has_consumed_energy() const { return false; }
|
||||
|
||||
/// returns true if battery monitor instance provides current info
|
||||
virtual bool has_current() const = 0;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user