CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp
Views: 1798
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_BattMonitor_config.h"
17
18
#if AP_BATTERY_ENABLED
19
20
#include <AP_Common/AP_Common.h>
21
#include <AP_HAL/AP_HAL.h>
22
#include "AP_BattMonitor.h"
23
#include "AP_BattMonitor_Backend.h"
24
25
#if AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED
26
#include "AP_ESC_Telem/AP_ESC_Telem.h"
27
#endif
28
29
/*
30
All backends use the same parameter table and set of indices. Therefore, two
31
backends must not use the same index. The list of used indices and
32
corresponding backends is below.
33
34
1-6: AP_BattMonitor_Analog.cpp
35
10-11: AP_BattMonitor_SMBus.cpp
36
20: AP_BattMonitor_Sum.cpp
37
22-24: AP_BattMonitor_INA3221.cpp
38
25-26: AP_BattMonitor_INA2xx.cpp
39
27-28: AP_BattMonitor_INA2xx.cpp, AP_BattMonitor_INA239.cpp (legacy duplication)
40
30: AP_BattMonitor_DroneCAN.cpp
41
36: AP_BattMonitor_ESC.cpp
42
40-43: AP_BattMonitor_FuelLevel_Analog.cpp
43
45-48: AP_BattMonitor_FuelLevel_Analog.cpp
44
50-51: AP_BattMonitor_Synthetic_Current.cpp
45
56-61: AP_BattMonitor_AD7091R5.cpp
46
47
Usage does not need to be contiguous. The maximum possible index is 63.
48
*/
49
50
/*
51
base class constructor.
52
This incorporates initialisation as well.
53
*/
54
AP_BattMonitor_Backend::AP_BattMonitor_Backend(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state,
55
AP_BattMonitor_Params &params) :
56
_mon(mon),
57
_state(mon_state),
58
_params(params)
59
{
60
}
61
62
// capacity_remaining_pct - returns true if the battery % is available and writes to the percentage argument
63
// return false if the battery is unhealthy, does not have current monitoring, or the pack_capacity is too small
64
bool AP_BattMonitor_Backend::capacity_remaining_pct(uint8_t &percentage) const
65
{
66
// we consider anything under 10 mAh as being an invalid capacity and so will be our measurement of remaining capacity
67
if ( _params._pack_capacity <= 10) {
68
return false;
69
}
70
71
// the monitor must have current readings in order to estimate consumed_mah and be healthy
72
if (!has_current() || !_state.healthy) {
73
return false;
74
}
75
if (isnan(_state.consumed_mah) || _params._pack_capacity <= 0) {
76
return false;
77
}
78
79
const float mah_remaining = _params._pack_capacity - _state.consumed_mah;
80
percentage = constrain_float(100 * mah_remaining / _params._pack_capacity, 0, UINT8_MAX);
81
return true;
82
}
83
84
// update battery resistance estimate
85
// faster rates of change of the current and voltage readings cause faster updates to the resistance estimate
86
// the battery resistance is calculated by comparing the latest current and voltage readings to a low-pass filtered current and voltage
87
// high current steps are integrated into the resistance estimate by varying the time constant of the resistance filter
88
void AP_BattMonitor_Backend::update_resistance_estimate()
89
{
90
// return immediately if no current
91
if (!has_current() || !is_positive(_state.current_amps)) {
92
return;
93
}
94
95
// update maximum current seen since startup and protect against divide by zero
96
_current_max_amps = MAX(_current_max_amps, _state.current_amps);
97
float current_delta = _state.current_amps - _current_filt_amps;
98
if (is_zero(current_delta)) {
99
return;
100
}
101
102
// update reference voltage and current
103
if (_state.voltage > _resistance_voltage_ref) {
104
_resistance_voltage_ref = _state.voltage;
105
_resistance_current_ref = _state.current_amps;
106
}
107
108
// calculate time since last update
109
uint32_t now = AP_HAL::millis();
110
float loop_interval = (now - _resistance_timer_ms) * 0.001f;
111
_resistance_timer_ms = now;
112
113
// estimate short-term resistance
114
float filt_alpha = constrain_float(loop_interval/(loop_interval + AP_BATT_MONITOR_RES_EST_TC_1), 0.0f, 0.5f);
115
float resistance_alpha = MIN(1, AP_BATT_MONITOR_RES_EST_TC_2*fabsf((_state.current_amps-_current_filt_amps)/_current_max_amps));
116
float resistance_estimate = -(_state.voltage-_voltage_filt)/current_delta;
117
if (is_positive(resistance_estimate)) {
118
_state.resistance = _state.resistance*(1-resistance_alpha) + resistance_estimate*resistance_alpha;
119
}
120
121
// calculate maximum resistance
122
if ((_resistance_voltage_ref > _state.voltage) && (_state.current_amps > _resistance_current_ref)) {
123
float resistance_max = (_resistance_voltage_ref - _state.voltage) / (_state.current_amps - _resistance_current_ref);
124
_state.resistance = MIN(_state.resistance, resistance_max);
125
}
126
127
// update the filtered voltage and currents
128
_voltage_filt = _voltage_filt*(1-filt_alpha) + _state.voltage*filt_alpha;
129
_current_filt_amps = _current_filt_amps*(1-filt_alpha) + _state.current_amps*filt_alpha;
130
131
// update estimated voltage without sag
132
_state.voltage_resting_estimate = _state.voltage + _state.current_amps * _state.resistance;
133
}
134
135
// return true if state of health can be provided and fills in soh_pct argument
136
bool AP_BattMonitor_Backend::get_state_of_health_pct(uint8_t &soh_pct) const
137
{
138
if (!_state.has_state_of_health_pct) {
139
return false;
140
}
141
soh_pct = _state.state_of_health_pct;
142
return true;
143
}
144
145
float AP_BattMonitor_Backend::voltage_resting_estimate() const
146
{
147
// resting voltage should always be greater than or equal to the raw voltage
148
return MAX(_state.voltage, _state.voltage_resting_estimate);
149
}
150
151
AP_BattMonitor::Failsafe AP_BattMonitor_Backend::update_failsafes(void)
152
{
153
const uint32_t now = AP_HAL::millis();
154
155
bool low_voltage, low_capacity, critical_voltage, critical_capacity;
156
check_failsafe_types(low_voltage, low_capacity, critical_voltage, critical_capacity);
157
158
if (critical_voltage) {
159
// this is the first time our voltage has dropped below minimum so start timer
160
if (_state.critical_voltage_start_ms == 0) {
161
_state.critical_voltage_start_ms = now;
162
} else if (_params._low_voltage_timeout > 0 &&
163
now - _state.critical_voltage_start_ms > uint32_t(_params._low_voltage_timeout)*1000U) {
164
return AP_BattMonitor::Failsafe::Critical;
165
}
166
} else {
167
// acceptable voltage so reset timer
168
_state.critical_voltage_start_ms = 0;
169
}
170
171
if (critical_capacity) {
172
return AP_BattMonitor::Failsafe::Critical;
173
}
174
175
if (low_voltage) {
176
// this is the first time our voltage has dropped below minimum so start timer
177
if (_state.low_voltage_start_ms == 0) {
178
_state.low_voltage_start_ms = now;
179
} else if (_params._low_voltage_timeout > 0 &&
180
now - _state.low_voltage_start_ms > uint32_t(_params._low_voltage_timeout)*1000U) {
181
return AP_BattMonitor::Failsafe::Low;
182
}
183
} else {
184
// acceptable voltage so reset timer
185
_state.low_voltage_start_ms = 0;
186
}
187
188
if (low_capacity) {
189
return AP_BattMonitor::Failsafe::Low;
190
}
191
192
// 5 second health timeout
193
if ((now - _state.last_healthy_ms) > 5000) {
194
return AP_BattMonitor::Failsafe::Unhealthy;
195
}
196
197
// if we've gotten this far then battery is ok
198
return AP_BattMonitor::Failsafe::None;
199
}
200
201
static bool update_check(size_t buflen, char *buffer, bool failed, const char *message)
202
{
203
if (failed) {
204
strncpy(buffer, message, buflen);
205
return false;
206
}
207
return true;
208
}
209
210
bool AP_BattMonitor_Backend::arming_checks(char * buffer, size_t buflen) const
211
{
212
bool low_voltage, low_capacity, critical_voltage, critical_capacity;
213
check_failsafe_types(low_voltage, low_capacity, critical_voltage, critical_capacity);
214
215
bool below_arming_voltage = is_positive(_params._arming_minimum_voltage) &&
216
(_state.voltage < _params._arming_minimum_voltage);
217
bool below_arming_capacity = (_params._arming_minimum_capacity > 0) &&
218
((_params._pack_capacity - _state.consumed_mah) < _params._arming_minimum_capacity);
219
bool fs_capacity_inversion = is_positive(_params._critical_capacity) &&
220
is_positive(_params._low_capacity) &&
221
!(_params._low_capacity > _params._critical_capacity);
222
bool fs_voltage_inversion = is_positive(_params._critical_voltage) &&
223
is_positive(_params._low_voltage) &&
224
!(_params._low_voltage > _params._critical_voltage);
225
226
bool result = update_check(buflen, buffer, !_state.healthy, "unhealthy");
227
result = result && update_check(buflen, buffer, below_arming_voltage, "below minimum arming voltage");
228
result = result && update_check(buflen, buffer, below_arming_capacity, "below minimum arming capacity");
229
result = result && update_check(buflen, buffer, low_voltage, "low voltage failsafe");
230
result = result && update_check(buflen, buffer, low_capacity, "low capacity failsafe");
231
result = result && update_check(buflen, buffer, critical_voltage, "critical voltage failsafe");
232
result = result && update_check(buflen, buffer, critical_capacity, "critical capacity failsafe");
233
result = result && update_check(buflen, buffer, fs_capacity_inversion, "capacity failsafe critical >= low");
234
result = result && update_check(buflen, buffer, fs_voltage_inversion, "voltage failsafe critical >= low");
235
236
return result;
237
}
238
239
void AP_BattMonitor_Backend::check_failsafe_types(bool &low_voltage, bool &low_capacity, bool &critical_voltage, bool &critical_capacity) const
240
{
241
// use voltage or sag compensated voltage
242
float voltage_used;
243
switch (_params.failsafe_voltage_source()) {
244
case AP_BattMonitor_Params::BattMonitor_LowVoltageSource_Raw:
245
default:
246
voltage_used = _state.voltage;
247
break;
248
case AP_BattMonitor_Params::BattMonitor_LowVoltageSource_SagCompensated:
249
voltage_used = voltage_resting_estimate();
250
break;
251
}
252
253
// check critical battery levels
254
if ((voltage_used > 0) && (_params._critical_voltage > 0) && (voltage_used < _params._critical_voltage)) {
255
critical_voltage = true;
256
} else {
257
critical_voltage = false;
258
}
259
260
// check capacity failsafe if current monitoring is enabled
261
if (has_current() && (_params._critical_capacity > 0) &&
262
((_params._pack_capacity - _state.consumed_mah) < _params._critical_capacity)) {
263
critical_capacity = true;
264
} else {
265
critical_capacity = false;
266
}
267
268
if ((voltage_used > 0) && (_params._low_voltage > 0) && (voltage_used < _params._low_voltage)) {
269
low_voltage = true;
270
} else {
271
low_voltage = false;
272
}
273
274
// check capacity if current monitoring is enabled
275
if (has_current() && (_params._low_capacity > 0) &&
276
((_params._pack_capacity - _state.consumed_mah) < _params._low_capacity)) {
277
low_capacity = true;
278
} else {
279
low_capacity = false;
280
}
281
}
282
283
#if AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED
284
void AP_BattMonitor_Backend::update_esc_telem_outbound()
285
{
286
const uint8_t esc_index = _params._esc_telem_outbound_index;
287
if (esc_index == 0 || !_state.healthy) {
288
// Disabled if there's no ESC identified to route the data to or if the battery is unhealthy
289
return;
290
}
291
292
AP_ESC_Telem_Backend::TelemetryData telem {};
293
294
uint16_t type = AP_ESC_Telem_Backend::TelemetryType::VOLTAGE;
295
telem.voltage = _state.voltage; // all battery backends have voltage
296
297
if (has_current()) {
298
telem.current = _state.current_amps;
299
type |= AP_ESC_Telem_Backend::TelemetryType::CURRENT;
300
}
301
302
if (has_consumed_energy()) {
303
telem.consumption_mah = _state.consumed_mah;
304
type |= AP_ESC_Telem_Backend::TelemetryType::CONSUMPTION;
305
}
306
307
float temperature_c;
308
if (_mon.get_temperature(temperature_c, _state.instance)) {
309
// get the temperature from the frontend so we check for external temperature
310
telem.temperature_cdeg = temperature_c * 100;
311
type |= AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE;
312
}
313
314
AP::esc_telem().update_telem_data(esc_index-1, telem, type);
315
}
316
#endif
317
318
// returns true if battery monitor provides temperature
319
bool AP_BattMonitor_Backend::get_temperature(float &temperature) const
320
{
321
#if AP_TEMPERATURE_SENSOR_ENABLED
322
if (_state.temperature_external_use) {
323
temperature = _state.temperature_external;
324
return true;
325
}
326
#endif
327
328
temperature = _state.temperature;
329
330
return has_temperature();
331
}
332
333
/*
334
default implementation for reset_remaining(). This sets consumed_wh
335
and consumed_mah based on the given percentage. Use percentage=100
336
for a full battery
337
*/
338
bool AP_BattMonitor_Backend::reset_remaining(float percentage)
339
{
340
percentage = constrain_float(percentage, 0, 100);
341
const float used_proportion = (100.0f - percentage) * 0.01f;
342
_state.consumed_mah = used_proportion * _params._pack_capacity;
343
// without knowing the history we can't do consumed_wh
344
// accurately. Best estimate is based on current voltage. This
345
// will be good when resetting the battery to a value close to
346
// full charge
347
_state.consumed_wh = _state.consumed_mah * 0.001f * _state.voltage;
348
349
// reset failsafe state for this backend
350
_state.failsafe = update_failsafes();
351
352
return true;
353
}
354
355
/*
356
update consumed mAh and Wh
357
*/
358
void AP_BattMonitor_Backend::update_consumed(AP_BattMonitor::BattMonitor_State &state, uint32_t dt_us)
359
{
360
// update total current drawn since startup
361
if (state.last_time_micros != 0 && dt_us < 2000000) {
362
const float mah = calculate_mah(state.current_amps, dt_us);
363
state.consumed_mah += mah;
364
state.consumed_wh += 0.001 * mah * state.voltage;
365
}
366
}
367
368
#endif // AP_BATTERY_ENABLED
369
370