AP_BattMonitor: NFC rename functions and variables to match their functionality

This commit is contained in:
Dr.-Ing. Amilcar Do Carmo Lucas 2018-02-15 17:10:36 +01:00 committed by Francisco Ferreira
parent bc86ca0e3c
commit 6cbeb73d1b
7 changed files with 17 additions and 17 deletions

View File

@ -257,16 +257,16 @@ float AP_BattMonitor::current_amps(uint8_t instance) const {
} }
} }
/// current_total_mah - returns total current drawn since start-up in amp-hours /// consumed_mah - returns total current drawn since start-up in milliampere.hours
float AP_BattMonitor::current_total_mah(uint8_t instance) const { float AP_BattMonitor::consumed_mah(uint8_t instance) const {
if (instance < _num_instances) { if (instance < _num_instances) {
return state[instance].current_total_mah; return state[instance].consumed_mah;
} else { } else {
return 0.0f; return 0.0f;
} }
} }
/// consumed_wh - returns energy consumed since start-up in watt-hours /// consumed_wh - returns energy consumed since start-up in Watt.hours
float AP_BattMonitor::consumed_wh(uint8_t instance) const { float AP_BattMonitor::consumed_wh(uint8_t instance) const {
if (instance < _num_instances) { if (instance < _num_instances) {
return state[instance].consumed_wh; return state[instance].consumed_wh;
@ -331,7 +331,7 @@ bool AP_BattMonitor::exhausted(uint8_t instance, float low_voltage, float min_ca
// check capacity if current monitoring is enabled // check capacity if current monitoring is enabled
if (has_current(instance) && (min_capacity_mah > 0) && if (has_current(instance) && (min_capacity_mah > 0) &&
(_params[instance]._pack_capacity - state[instance].current_total_mah < min_capacity_mah)) { (_params[instance]._pack_capacity - state[instance].consumed_mah < min_capacity_mah)) {
return true; return true;
} }

View File

@ -56,12 +56,12 @@ public:
cells cell_voltages; // battery cell voltages in millivolts, 10 cells matches the MAVLink spec cells cell_voltages; // battery cell voltages in millivolts, 10 cells matches the MAVLink spec
float voltage; // voltage in volts float voltage; // voltage in volts
float current_amps; // current in amperes float current_amps; // current in amperes
float current_total_mah; // total current draw since start-up float consumed_mah; // total current draw in milliampere.hours since start-up
float consumed_wh; // total energy consumed in Wh since start-up float consumed_wh; // total energy consumed in Watt.hours since start-up
uint32_t last_time_micros; // time when voltage and current was last read 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 uint32_t low_voltage_start_ms; // time when voltage dropped below the minimum
float temperature; // battery temperature in celsius float temperature; // battery temperature in celsius
uint32_t temperature_time; // timestamp of the last recieved temperature message uint32_t temperature_time; // timestamp of the last received temperature message
float voltage_resting_estimate; // voltage with sag removed based on current and resistance estimate float voltage_resting_estimate; // voltage with sag removed based on current and resistance estimate
float resistance; // resistance calculated by comparing resting voltage vs in flight voltage float resistance; // resistance calculated by comparing resting voltage vs in flight voltage
bool healthy; // battery monitor is communicating correctly bool healthy; // battery monitor is communicating correctly
@ -101,11 +101,11 @@ public:
float current_amps(uint8_t instance) const; float current_amps(uint8_t instance) const;
float current_amps() const { return current_amps(AP_BATT_PRIMARY_INSTANCE); } float current_amps() const { return current_amps(AP_BATT_PRIMARY_INSTANCE); }
/// current_total_mah - returns total current drawn since start-up in amp-hours /// consumed_mah - returns total current drawn since start-up in milliampere.hours
float current_total_mah(uint8_t instance) const; float consumed_mah(uint8_t instance) const;
float current_total_mah() const { return current_total_mah(AP_BATT_PRIMARY_INSTANCE); } float consumed_mah() const { return consumed_mah(AP_BATT_PRIMARY_INSTANCE); }
/// consumed_wh - returns total energy drawn since start-up in watt-hours /// consumed_wh - returns total energy drawn since start-up in watt.hours
float consumed_wh(uint8_t instance) const; float consumed_wh(uint8_t instance) const;
float consumed_wh() const { return consumed_wh(AP_BATT_PRIMARY_INSTANCE); } float consumed_wh() const { return consumed_wh(AP_BATT_PRIMARY_INSTANCE); }

View File

@ -45,7 +45,7 @@ AP_BattMonitor_Analog::read()
if (_state.last_time_micros != 0 && dt < 2000000.0f) { if (_state.last_time_micros != 0 && dt < 2000000.0f) {
// .0002778 is 1/3600 (conversion to hours) // .0002778 is 1/3600 (conversion to hours)
float mah = _state.current_amps * dt * 0.0000002778f; float mah = _state.current_amps * dt * 0.0000002778f;
_state.current_total_mah += mah; _state.consumed_mah += mah;
_state.consumed_wh += 0.001f * mah * _state.voltage; _state.consumed_wh += 0.001f * mah * _state.voltage;
} }

View File

@ -33,7 +33,7 @@ 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 the % battery capacity remaining (0 ~ 100)
uint8_t AP_BattMonitor_Backend::capacity_remaining_pct() const uint8_t AP_BattMonitor_Backend::capacity_remaining_pct() const
{ {
float mah_remaining = _params._pack_capacity - _state.current_total_mah; float mah_remaining = _params._pack_capacity - _state.consumed_mah;
if ( _params._pack_capacity > 10 ) { // a very very small battery if ( _params._pack_capacity > 10 ) { // a very very small battery
return (100 * (mah_remaining) / _params._pack_capacity); return (100 * (mah_remaining) / _params._pack_capacity);
} else { } else {

View File

@ -214,7 +214,7 @@ void AP_BattMonitor_Bebop::read(void)
_state.voltage = vbat; _state.voltage = vbat;
_state.last_time_micros = tnow; _state.last_time_micros = tnow;
_state.healthy = true; _state.healthy = true;
_state.current_total_mah = capacity - (remaining * capacity) / 100.0f; _state.consumed_mah = capacity - (remaining * capacity) / 100.0f;
} }
#endif #endif

View File

@ -59,7 +59,7 @@ bool AP_BattMonitor_SMBus::read_remaining_capacity(void)
if (capacity > 0) { if (capacity > 0) {
uint16_t data; uint16_t data;
if (read_word(BATTMONITOR_SMBUS_REMAINING_CAPACITY, data)) { if (read_word(BATTMONITOR_SMBUS_REMAINING_CAPACITY, data)) {
_state.current_total_mah = MAX(0, capacity - data); _state.consumed_mah = MAX(0, capacity - data);
return true; return true;
} }
} }

View File

@ -50,7 +50,7 @@ void loop()
hal.console->printf("\nVoltage: %.2f \tCurrent: %.2f \tTotCurr:%.2f", hal.console->printf("\nVoltage: %.2f \tCurrent: %.2f \tTotCurr:%.2f",
(double)battery_mon.voltage(), (double)battery_mon.voltage(),
(double)battery_mon.current_amps(), (double)battery_mon.current_amps(),
(double)battery_mon.current_total_mah()); (double)battery_mon.consumed_mah());
} }
// delay 1ms // delay 1ms