Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415#include "AP_BattMonitor_config.h"1617#if AP_BATTERY_ENABLED1819#include <AP_Common/AP_Common.h>20#include <AP_HAL/AP_HAL.h>21#include "AP_BattMonitor.h"22#include "AP_BattMonitor_Backend.h"2324#if AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED25#include "AP_ESC_Telem/AP_ESC_Telem.h"26#endif2728/*29All backends use the same parameter table and set of indices. Therefore, two30backends must not use the same index. The list of used indices and31corresponding backends is below.32331-6: AP_BattMonitor_Analog.cpp3410-11: AP_BattMonitor_SMBus.cpp3520: AP_BattMonitor_Sum.cpp3622-24: AP_BattMonitor_INA3221.cpp3725-26: AP_BattMonitor_INA2xx.cpp3827-28: AP_BattMonitor_INA2xx.cpp, AP_BattMonitor_INA239.cpp (legacy duplication)3930: AP_BattMonitor_DroneCAN.cpp4036: AP_BattMonitor_ESC.cpp4140-43: AP_BattMonitor_FuelLevel_Analog.cpp4245-48: AP_BattMonitor_FuelLevel_Analog.cpp4350-51: AP_BattMonitor_Synthetic_Current.cpp4456-61: AP_BattMonitor_AD7091R5.cpp4546Usage does not need to be contiguous. The maximum possible index is 63.47*/4849/*50base class constructor.51This incorporates initialisation as well.52*/53AP_BattMonitor_Backend::AP_BattMonitor_Backend(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state,54AP_BattMonitor_Params ¶ms) :55_mon(mon),56_state(mon_state),57_params(params)58{59}6061// capacity_remaining_pct - returns true if the battery % is available and writes to the percentage argument62// return false if the battery is unhealthy, does not have current monitoring, or the pack_capacity is too small63bool AP_BattMonitor_Backend::capacity_remaining_pct(uint8_t &percentage) const64{65// we consider anything under 10 mAh as being an invalid capacity and so will be our measurement of remaining capacity66if ( _params._pack_capacity <= 10) {67return false;68}6970// the monitor must have current readings in order to estimate consumed_mah and be healthy71if (!has_current() || !_state.healthy) {72return false;73}74if (isnan(_state.consumed_mah) || _params._pack_capacity <= 0) {75return false;76}7778const float mah_remaining = _params._pack_capacity - _state.consumed_mah;79percentage = constrain_float(100 * mah_remaining / _params._pack_capacity, 0, UINT8_MAX);80return true;81}8283// update battery resistance estimate84// faster rates of change of the current and voltage readings cause faster updates to the resistance estimate85// the battery resistance is calculated by comparing the latest current and voltage readings to a low-pass filtered current and voltage86// high current steps are integrated into the resistance estimate by varying the time constant of the resistance filter87void AP_BattMonitor_Backend::update_resistance_estimate()88{89// return immediately if no current90if (!has_current() || !is_positive(_state.current_amps)) {91return;92}9394// update maximum current seen since startup and protect against divide by zero95_current_max_amps = MAX(_current_max_amps, _state.current_amps);96float current_delta = _state.current_amps - _current_filt_amps;97if (is_zero(current_delta)) {98return;99}100101// update reference voltage and current102if (_state.voltage > _resistance_voltage_ref) {103_resistance_voltage_ref = _state.voltage;104_resistance_current_ref = _state.current_amps;105}106107// calculate time since last update108uint32_t now = AP_HAL::millis();109float loop_interval = (now - _resistance_timer_ms) * 0.001f;110_resistance_timer_ms = now;111112// estimate short-term resistance113float filt_alpha = constrain_float(loop_interval/(loop_interval + AP_BATT_MONITOR_RES_EST_TC_1), 0.0f, 0.5f);114float resistance_alpha = MIN(1, AP_BATT_MONITOR_RES_EST_TC_2*fabsf((_state.current_amps-_current_filt_amps)/_current_max_amps));115float resistance_estimate = -(_state.voltage-_voltage_filt)/current_delta;116if (is_positive(resistance_estimate)) {117_state.resistance = _state.resistance*(1-resistance_alpha) + resistance_estimate*resistance_alpha;118}119120// calculate maximum resistance121if ((_resistance_voltage_ref > _state.voltage) && (_state.current_amps > _resistance_current_ref)) {122float resistance_max = (_resistance_voltage_ref - _state.voltage) / (_state.current_amps - _resistance_current_ref);123_state.resistance = MIN(_state.resistance, resistance_max);124}125126// update the filtered voltage and currents127_voltage_filt = _voltage_filt*(1-filt_alpha) + _state.voltage*filt_alpha;128_current_filt_amps = _current_filt_amps*(1-filt_alpha) + _state.current_amps*filt_alpha;129130// update estimated voltage without sag131_state.voltage_resting_estimate = _state.voltage + _state.current_amps * _state.resistance;132}133134// return true if state of health can be provided and fills in soh_pct argument135bool AP_BattMonitor_Backend::get_state_of_health_pct(uint8_t &soh_pct) const136{137if (!_state.has_state_of_health_pct) {138return false;139}140soh_pct = _state.state_of_health_pct;141return true;142}143144float AP_BattMonitor_Backend::voltage_resting_estimate() const145{146// resting voltage should always be greater than or equal to the raw voltage147return MAX(_state.voltage, _state.voltage_resting_estimate);148}149150AP_BattMonitor::Failsafe AP_BattMonitor_Backend::update_failsafes(void)151{152const uint32_t now = AP_HAL::millis();153154bool low_voltage, low_capacity, critical_voltage, critical_capacity;155check_failsafe_types(low_voltage, low_capacity, critical_voltage, critical_capacity);156157if (critical_voltage) {158// this is the first time our voltage has dropped below minimum so start timer159if (_state.critical_voltage_start_ms == 0) {160_state.critical_voltage_start_ms = now;161} else if (_params._low_voltage_timeout > 0 &&162now - _state.critical_voltage_start_ms > uint32_t(_params._low_voltage_timeout)*1000U) {163return AP_BattMonitor::Failsafe::Critical;164}165} else {166// acceptable voltage so reset timer167_state.critical_voltage_start_ms = 0;168}169170if (critical_capacity) {171return AP_BattMonitor::Failsafe::Critical;172}173174if (low_voltage) {175// this is the first time our voltage has dropped below minimum so start timer176if (_state.low_voltage_start_ms == 0) {177_state.low_voltage_start_ms = now;178} else if (_params._low_voltage_timeout > 0 &&179now - _state.low_voltage_start_ms > uint32_t(_params._low_voltage_timeout)*1000U) {180return AP_BattMonitor::Failsafe::Low;181}182} else {183// acceptable voltage so reset timer184_state.low_voltage_start_ms = 0;185}186187if (low_capacity) {188return AP_BattMonitor::Failsafe::Low;189}190191// 5 second health timeout192if ((now - _state.last_healthy_ms) > 5000) {193return AP_BattMonitor::Failsafe::Unhealthy;194}195196// if we've gotten this far then battery is ok197return AP_BattMonitor::Failsafe::None;198}199200static bool update_check(size_t buflen, char *buffer, bool failed, const char *message)201{202if (failed) {203strncpy(buffer, message, buflen);204return false;205}206return true;207}208209bool AP_BattMonitor_Backend::arming_checks(char * buffer, size_t buflen) const210{211bool low_voltage, low_capacity, critical_voltage, critical_capacity;212check_failsafe_types(low_voltage, low_capacity, critical_voltage, critical_capacity);213214bool below_arming_voltage = is_positive(_params._arming_minimum_voltage) &&215(_state.voltage < _params._arming_minimum_voltage);216bool below_arming_capacity = (_params._arming_minimum_capacity > 0) &&217((_params._pack_capacity - _state.consumed_mah) < _params._arming_minimum_capacity);218bool fs_capacity_inversion = is_positive(_params._critical_capacity) &&219is_positive(_params._low_capacity) &&220!(_params._low_capacity > _params._critical_capacity);221bool fs_voltage_inversion = is_positive(_params._critical_voltage) &&222is_positive(_params._low_voltage) &&223!(_params._low_voltage > _params._critical_voltage);224225bool result = update_check(buflen, buffer, !_state.healthy, "unhealthy");226result = result && update_check(buflen, buffer, below_arming_voltage, "below minimum arming voltage");227result = result && update_check(buflen, buffer, below_arming_capacity, "below minimum arming capacity");228result = result && update_check(buflen, buffer, low_voltage, "low voltage failsafe");229result = result && update_check(buflen, buffer, low_capacity, "low capacity failsafe");230result = result && update_check(buflen, buffer, critical_voltage, "critical voltage failsafe");231result = result && update_check(buflen, buffer, critical_capacity, "critical capacity failsafe");232result = result && update_check(buflen, buffer, fs_capacity_inversion, "capacity failsafe critical >= low");233result = result && update_check(buflen, buffer, fs_voltage_inversion, "voltage failsafe critical >= low");234235return result;236}237238void AP_BattMonitor_Backend::check_failsafe_types(bool &low_voltage, bool &low_capacity, bool &critical_voltage, bool &critical_capacity) const239{240// use voltage or sag compensated voltage241float voltage_used;242switch (_params.failsafe_voltage_source()) {243case AP_BattMonitor_Params::BattMonitor_LowVoltageSource_Raw:244default:245voltage_used = _state.voltage;246break;247case AP_BattMonitor_Params::BattMonitor_LowVoltageSource_SagCompensated:248voltage_used = voltage_resting_estimate();249break;250}251252// check critical battery levels253if ((voltage_used > 0) && (_params._critical_voltage > 0) && (voltage_used < _params._critical_voltage)) {254critical_voltage = true;255} else {256critical_voltage = false;257}258259// check capacity failsafe if current monitoring is enabled260if (has_current() && (_params._critical_capacity > 0) &&261((_params._pack_capacity - _state.consumed_mah) < _params._critical_capacity)) {262critical_capacity = true;263} else {264critical_capacity = false;265}266267if ((voltage_used > 0) && (_params._low_voltage > 0) && (voltage_used < _params._low_voltage)) {268low_voltage = true;269} else {270low_voltage = false;271}272273// check capacity if current monitoring is enabled274if (has_current() && (_params._low_capacity > 0) &&275((_params._pack_capacity - _state.consumed_mah) < _params._low_capacity)) {276low_capacity = true;277} else {278low_capacity = false;279}280}281282#if AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED283void AP_BattMonitor_Backend::update_esc_telem_outbound()284{285const uint8_t esc_index = _params._esc_telem_outbound_index;286if (esc_index == 0 || !_state.healthy) {287// Disabled if there's no ESC identified to route the data to or if the battery is unhealthy288return;289}290291AP_ESC_Telem_Backend::TelemetryData telem {};292293uint16_t type = AP_ESC_Telem_Backend::TelemetryType::VOLTAGE;294telem.voltage = _state.voltage; // all battery backends have voltage295296if (has_current()) {297telem.current = _state.current_amps;298type |= AP_ESC_Telem_Backend::TelemetryType::CURRENT;299}300301if (has_consumed_energy()) {302telem.consumption_mah = _state.consumed_mah;303type |= AP_ESC_Telem_Backend::TelemetryType::CONSUMPTION;304}305306float temperature_c;307if (_mon.get_temperature(temperature_c, _state.instance)) {308// get the temperature from the frontend so we check for external temperature309telem.temperature_cdeg = temperature_c * 100;310type |= AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE;311}312313AP::esc_telem().update_telem_data(esc_index-1, telem, type);314}315#endif316317// returns true if battery monitor provides temperature318bool AP_BattMonitor_Backend::get_temperature(float &temperature) const319{320#if AP_TEMPERATURE_SENSOR_ENABLED321if (_state.temperature_external_use) {322temperature = _state.temperature_external;323return true;324}325#endif326327temperature = _state.temperature;328329return has_temperature();330}331332/*333default implementation for reset_remaining(). This sets consumed_wh334and consumed_mah based on the given percentage. Use percentage=100335for a full battery336*/337bool AP_BattMonitor_Backend::reset_remaining(float percentage)338{339percentage = constrain_float(percentage, 0, 100);340const float used_proportion = (100.0f - percentage) * 0.01f;341_state.consumed_mah = used_proportion * _params._pack_capacity;342// without knowing the history we can't do consumed_wh343// accurately. Best estimate is based on current voltage. This344// will be good when resetting the battery to a value close to345// full charge346_state.consumed_wh = _state.consumed_mah * 0.001f * _state.voltage;347348// reset failsafe state for this backend349_state.failsafe = update_failsafes();350351return true;352}353354/*355update consumed mAh and Wh356*/357void AP_BattMonitor_Backend::update_consumed(AP_BattMonitor::BattMonitor_State &state, uint32_t dt_us)358{359// update total current drawn since startup360if (state.last_time_micros != 0 && dt_us < 2000000) {361const float mah = calculate_mah(state.current_amps, dt_us);362state.consumed_mah += mah;363state.consumed_wh += 0.001 * mah * state.voltage;364}365}366367#endif // AP_BATTERY_ENABLED368369370