diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.cpp b/libraries/AP_BattMonitor/AP_BattMonitor.cpp index d2d5c81070..6dfd0ac7a6 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor.cpp @@ -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 -float AP_BattMonitor::current_total_mah(uint8_t instance) const { +/// 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].current_total_mah; + return state[instance].consumed_mah; } else { 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 { if (instance < _num_instances) { 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 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; } diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.h b/libraries/AP_BattMonitor/AP_BattMonitor.h index 3a7a5d159c..5b457dce53 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor.h @@ -56,12 +56,12 @@ public: cells cell_voltages; // battery cell voltages in millivolts, 10 cells matches the MAVLink spec 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 + float consumed_mah; // total current draw in milliampere.hours 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 low_voltage_start_ms; // time when voltage dropped below the minimum 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 resistance; // resistance calculated by comparing resting voltage vs in flight voltage bool healthy; // battery monitor is communicating correctly @@ -101,11 +101,11 @@ public: float current_amps(uint8_t instance) const; float current_amps() const { return current_amps(AP_BATT_PRIMARY_INSTANCE); } - /// current_total_mah - returns total current drawn since start-up in amp-hours - float current_total_mah(uint8_t instance) const; - float current_total_mah() const { return current_total_mah(AP_BATT_PRIMARY_INSTANCE); } + /// 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); } - /// 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() const { return consumed_wh(AP_BATT_PRIMARY_INSTANCE); } diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Analog.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Analog.cpp index 46d43a12e3..6baa1cebfd 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Analog.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Analog.cpp @@ -45,7 +45,7 @@ AP_BattMonitor_Analog::read() if (_state.last_time_micros != 0 && dt < 2000000.0f) { // .0002778 is 1/3600 (conversion to hours) 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; } diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp index 24f1f1484d..84f711f92e 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp @@ -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) 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 return (100 * (mah_remaining) / _params._pack_capacity); } else { diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp index ee224c7e5c..c43e41671e 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp @@ -214,7 +214,7 @@ void AP_BattMonitor_Bebop::read(void) _state.voltage = vbat; _state.last_time_micros = tnow; _state.healthy = true; - _state.current_total_mah = capacity - (remaining * capacity) / 100.0f; + _state.consumed_mah = capacity - (remaining * capacity) / 100.0f; } #endif diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus.cpp index f35930bdfe..d04e3f9f02 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus.cpp @@ -59,7 +59,7 @@ bool AP_BattMonitor_SMBus::read_remaining_capacity(void) if (capacity > 0) { uint16_t 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; } } diff --git a/libraries/AP_BattMonitor/examples/AP_BattMonitor_test/AP_BattMonitor_test.cpp b/libraries/AP_BattMonitor/examples/AP_BattMonitor_test/AP_BattMonitor_test.cpp index 7e2315827f..6c813aeb2c 100644 --- a/libraries/AP_BattMonitor/examples/AP_BattMonitor_test/AP_BattMonitor_test.cpp +++ b/libraries/AP_BattMonitor/examples/AP_BattMonitor_test/AP_BattMonitor_test.cpp @@ -50,7 +50,7 @@ void loop() hal.console->printf("\nVoltage: %.2f \tCurrent: %.2f \tTotCurr:%.2f", (double)battery_mon.voltage(), (double)battery_mon.current_amps(), - (double)battery_mon.current_total_mah()); + (double)battery_mon.consumed_mah()); } // delay 1ms