APM:Libraries
AP_BattMonitor_Backend.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 #include <AP_Common/AP_Common.h>
17 #include <AP_HAL/AP_HAL.h>
18 #include "AP_BattMonitor.h"
19 #include "AP_BattMonitor_Backend.h"
20 
21 /*
22  base class constructor.
23  This incorporates initialisation as well.
24 */
26  AP_BattMonitor_Params &params) :
27  _mon(mon),
28  _state(mon_state),
29  _params(params)
30 {
31 }
32 
35 {
36  float mah_remaining = _params._pack_capacity - _state.consumed_mah;
37  if ( _params._pack_capacity > 10 ) { // a very very small battery
38  return (100 * (mah_remaining) / _params._pack_capacity);
39  } else {
40  return 0;
41  }
42 }
43 
44 // update battery resistance estimate
45 // faster rates of change of the current and voltage readings cause faster updates to the resistance estimate
46 // the battery resistance is calculated by comparing the latest current and voltage readings to a low-pass filtered current and voltage
47 // high current steps are integrated into the resistance estimate by varying the time constant of the resistance filter
49 {
50  // return immediately if no current
52  return;
53  }
54 
55  // update maximum current seen since startup and protect against divide by zero
57  float current_delta = _state.current_amps - _current_filt_amps;
58  if (is_zero(current_delta)) {
59  return;
60  }
61 
62  // update reference voltage and current
66  }
67 
68  // calculate time since last update
69  uint32_t now = AP_HAL::millis();
70  float loop_interval = (now - _resistance_timer_ms) / 1000.0f;
72 
73  // estimate short-term resistance
74  float filt_alpha = constrain_float(loop_interval/(loop_interval + AP_BATT_MONITOR_RES_EST_TC_1), 0.0f, 0.5f);
76  float resistance_estimate = -(_state.voltage-_voltage_filt)/current_delta;
77  if (is_positive(resistance_estimate)) {
78  _state.resistance = _state.resistance*(1-resistance_alpha) + resistance_estimate*resistance_alpha;
79  }
80 
81  // calculate maximum resistance
84  _state.resistance = MIN(_state.resistance, resistance_max);
85  }
86 
87  // update the filtered voltage and currents
88  _voltage_filt = _voltage_filt*(1-filt_alpha) + _state.voltage*filt_alpha;
89  _current_filt_amps = _current_filt_amps*(1-filt_alpha) + _state.current_amps*filt_alpha;
90 
91  // update estimated voltage without sag
93 }
#define AP_BATT_MONITOR_RES_EST_TC_1
bool is_positive(const T fVal1)
Definition: AP_Math.h:50
AP_BattMonitor_Backend(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params &params)
AP_BattMonitor_Params & _params
#define MIN(a, b)
Definition: usb_conf.h:215
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
AP_Int32 _pack_capacity
offset voltage that is subtracted from current pin before conversion to amps
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
uint32_t millis()
Definition: system.cpp:157
#define AP_BATT_MONITOR_RES_EST_TC_2
virtual bool has_current() const =0
returns true if battery monitor instance provides current info
uint8_t capacity_remaining_pct() const
capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
Common definitions and utility routines for the ArduPilot libraries.
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
AP_BattMonitor::BattMonitor_State & _state