AP_BattMonitor: Refactor interface for fetching current related data

This commit is contained in:
Michael du Breuil 2019-07-07 14:34:41 +00:00 committed by WickedShell
parent 9d20a13cd4
commit 0a4e3a77b3
3 changed files with 22 additions and 51 deletions

View File

@ -258,28 +258,6 @@ 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
{
if (instance < _num_instances && drivers[instance] != nullptr && _params[instance].type() != AP_BattMonitor_Params::BattMonitor_TYPE_NONE) {
return drivers[instance]->has_current();
}
// not monitoring current
return false;
}
/// voltage - returns battery voltage in volts
float AP_BattMonitor::voltage(uint8_t instance) const
{
@ -302,29 +280,32 @@ float AP_BattMonitor::voltage_resting_estimate(uint8_t instance) const
}
/// current_amps - returns the instantaneous current draw in amperes
float AP_BattMonitor::current_amps(uint8_t instance) const {
if (instance < _num_instances) {
return state[instance].current_amps;
bool AP_BattMonitor::current_amps(float &current, uint8_t instance) const {
if ((instance < _num_instances) && (drivers[instance] != nullptr) && drivers[instance]->has_current()) {
current = state[instance].current_amps;
return true;
} else {
return 0.0f;
return false;
}
}
/// consumed_mah - returns total current drawn since start-up in milliampere.hours
float AP_BattMonitor::consumed_mah(uint8_t instance) const {
if (instance < _num_instances) {
return state[instance].consumed_mah;
bool AP_BattMonitor::consumed_mah(float &mah, const uint8_t instance) const {
if ((instance < _num_instances) && (drivers[instance] != nullptr) && drivers[instance]->has_current()) {
mah = state[instance].consumed_mah;
return true;
} else {
return 0.0f;
return false;
}
}
/// 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;
bool AP_BattMonitor::consumed_wh(float &wh, const uint8_t instance) const {
if (instance < _num_instances && drivers[instance] != nullptr && drivers[instance]->has_consumed_energy()) {
wh = state[instance].consumed_wh;
return true;
} else {
return 0.0f;
return false;
}
}
@ -377,7 +358,7 @@ void AP_BattMonitor::check_failsafes(void)
}
gcs().send_text(MAV_SEVERITY_WARNING, "Battery %d is %s %.2fV used %.0f mAh", i + 1, type_str,
(double)voltage(i), (double)consumed_mah(i));
(double)voltage(i), (double)state[i].consumed_mah);
_has_triggered_failsafe = true;
AP_Notify::flags.failsafe_battery = true;
state[i].failsafe = type;

View File

@ -96,14 +96,6 @@ 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); }
/// voltage - returns battery voltage in millivolts
float voltage(uint8_t instance) const;
float voltage() const { return voltage(AP_BATT_PRIMARY_INSTANCE); }
@ -114,16 +106,13 @@ public:
float voltage_resting_estimate() const { return voltage_resting_estimate(AP_BATT_PRIMARY_INSTANCE); }
/// current_amps - returns the instantaneous current draw in amperes
float current_amps(uint8_t instance) const;
float current_amps() const { return current_amps(AP_BATT_PRIMARY_INSTANCE); }
bool current_amps(float &current, const uint8_t instance = AP_BATT_PRIMARY_INSTANCE) const WARN_IF_UNUSED;
/// consumed_mah - returns total current drawn since start-up in milliampere.hours
float consumed_mah(uint8_t instance) const;
float consumed_mah() const { return consumed_mah(AP_BATT_PRIMARY_INSTANCE); }
bool consumed_mah(float &mah, const uint8_t instance = AP_BATT_PRIMARY_INSTANCE) const WARN_IF_UNUSED;
/// 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); }
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)
virtual uint8_t capacity_remaining_pct(uint8_t instance) const;

View File

@ -37,8 +37,9 @@ AP_BattMonitor_Sum::read()
}
voltage_sum += _mon.voltage(i);
voltage_count++;
if (_mon.has_current(i)) {
current_sum += _mon.current_amps(i);
float current;
if (_mon.current_amps(current, i)) {
current_sum += current;
current_count++;
}
}