-
Notifications
You must be signed in to change notification settings - Fork 15.3k
Expand file tree
/
Copy pathbattery.cpp
More file actions
447 lines (366 loc) · 15.9 KB
/
battery.cpp
File metadata and controls
447 lines (366 loc) · 15.9 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
/****************************************************************************
*
* Copyright (c) 2019-2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file battery.cpp
*
* Library calls for battery functionality.
*
* @author Julian Oes <julian@oes.ch>
* @author Timothy Scott <timothy@auterion.com>
*/
#include "battery.h"
#include <mathlib/mathlib.h>
#include <cstring>
#include <px4_platform_common/defines.h>
using namespace time_literals;
using namespace matrix;
Battery::Battery(int index, ModuleParams *parent, const int sample_interval_us, const uint8_t source) :
ModuleParams(parent),
_index(index < 1 || index > 9 ? 1 : index),
_source(source)
{
const float expected_filter_dt = static_cast<float>(sample_interval_us) / 1_s;
_current_average_filter_a.setParameters(expected_filter_dt, 50.f);
_ocv_filter_v.setParameters(expected_filter_dt, 1.f);
_cell_voltage_filter_v.setParameters(expected_filter_dt, 1.f);
if (index > 9 || index < 1) {
PX4_ERR("Battery index must be between 1 and 9 (inclusive). Received %d. Defaulting to 1.", index);
}
// 16 chars for parameter name + null terminator
char param_name[17];
snprintf(param_name, sizeof(param_name), "BAT%d_V_EMPTY", _index);
_param_handles.v_empty = param_find(param_name);
if (_param_handles.v_empty == PARAM_INVALID) {
PX4_ERR("Could not find parameter with name %s", param_name);
}
snprintf(param_name, sizeof(param_name), "BAT%d_V_CHARGED", _index);
_param_handles.v_charged = param_find(param_name);
snprintf(param_name, sizeof(param_name), "BAT%d_N_CELLS", _index);
_param_handles.n_cells = param_find(param_name);
snprintf(param_name, sizeof(param_name), "BAT%d_CAPACITY", _index);
_param_handles.capacity = param_find(param_name);
snprintf(param_name, sizeof(param_name), "BAT%d_R_INTERNAL", _index);
_param_handles.r_internal = param_find(param_name);
snprintf(param_name, sizeof(param_name), "BAT%d_SOURCE", _index);
_param_handles.source = param_find(param_name);
snprintf(param_name, sizeof(param_name), "BAT%d_I_OVERWRITE", _index);
_param_handles.i_overwrite = param_find(param_name);
_param_handles.low_thr = param_find("BAT_LOW_THR");
_param_handles.crit_thr = param_find("BAT_CRIT_THR");
_param_handles.emergen_thr = param_find("BAT_EMERGEN_THR");
_param_handles.bat_avrg_current = param_find("BAT_AVRG_CURRENT");
updateParams();
}
void Battery::updateVoltage(const float voltage_v)
{
_voltage_v = voltage_v;
}
void Battery::updateCurrent(const float current_a)
{
// Overwrite the measured current if current overwrite is defined and vehicle is unarmed
if (!_armed && _params.i_overwrite > FLT_EPSILON) {
_current_a = _params.i_overwrite;
} else {
_current_a = current_a;
}
}
void Battery::updateTemperature(const float temperature_c)
{
_temperature_c = temperature_c;
}
void Battery::updateBatteryStatus(const hrt_abstime ×tamp)
{
updateDt(timestamp);
// Require minimum voltage otherwise override connected status
if (_voltage_v < LITHIUM_BATTERY_RECOGNITION_VOLTAGE) {
_connected = false;
}
if (!_connected || (_last_unconnected_timestamp == 0)) {
_last_unconnected_timestamp = timestamp;
}
// Wait with initializing filters to avoid relying on a voltage sample from the rising edge
_battery_initialized = _connected && (timestamp > _last_unconnected_timestamp + 2_s);
if (_connected && !_battery_initialized && _internal_resistance_initialized && _params.n_cells > 0) {
resetInternalResistanceEstimation(_voltage_v, _current_a);
}
sumDischarged(_current_a);
_state_of_charge_volt_based =
calculateStateOfChargeVoltageBased(_voltage_v, _current_a);
if (!_external_state_of_charge) {
estimateStateOfCharge();
}
computeScale();
if (_connected && _battery_initialized) {
_warning = determineWarning(_state_of_charge);
}
if (_vehicle_status_sub.updated()) {
vehicle_status_s vehicle_status;
if (_vehicle_status_sub.copy(&vehicle_status)) {
_armed = (vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED);
_vehicle_status_is_fw = (vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING);
}
}
}
battery_status_s Battery::getBatteryStatus()
{
battery_status_s battery_status{};
battery_status.voltage_v = _voltage_v;
battery_status.current_a = _current_a;
battery_status.current_average_a = _current_average_filter_a.getState();
battery_status.discharged_mah = _discharged_mah;
battery_status.remaining = _state_of_charge;
battery_status.scale = _scale;
battery_status.time_remaining_s = computeRemainingTime(_current_a);
battery_status.temperature = _temperature_c;
battery_status.cell_count = _params.n_cells;
battery_status.connected = _connected;
battery_status.source = _source;
battery_status.priority = _priority;
battery_status.capacity = static_cast<uint16_t>(_capacity_mah);
battery_status.id = static_cast<uint8_t>(_index);
battery_status.warning = _warning;
battery_status.timestamp = hrt_absolute_time();
battery_status.faults = determineFaults();
battery_status.internal_resistance_estimate = _internal_resistance_estimate;
battery_status.ocv_estimate = _voltage_v + _internal_resistance_estimate * _params.n_cells * _current_a;
battery_status.ocv_estimate_filtered = _ocv_filter_v.getState();
battery_status.volt_based_soc_estimate = _params.n_cells > 0 ? math::interpolate(_ocv_filter_v.getState() /
_params.n_cells,
_params.v_empty, _params.v_charged, 0.f, 1.f) : -1.f;
battery_status.voltage_prediction = _voltage_prediction;
battery_status.prediction_error = _prediction_error;
battery_status.estimation_covariance_norm = _estimation_covariance_norm;
return battery_status;
}
void Battery::publishBatteryStatus(const battery_status_s &battery_status)
{
if (_source == _params.source) {
_battery_status_pub.publish(battery_status);
}
}
void Battery::updateAndPublishBatteryStatus(const hrt_abstime ×tamp)
{
updateBatteryStatus(timestamp);
publishBatteryStatus(getBatteryStatus());
}
void Battery::updateDt(const hrt_abstime ×tamp)
{
if (_last_timestamp != 0) {
_dt = math::min((timestamp - _last_timestamp) / 1e6f, 2.f); // guard to a maximum 2 seconds dt
}
_last_timestamp = timestamp;
}
float Battery::sumDischarged(float current_a)
{
if (_dt > FLT_EPSILON && fabsf(current_a + 1.f) > FLT_EPSILON) {
// mAh since last loop: (current[A] * 1000 = [mA]) * (dt[s] / 3600 = [h])
// current = -1 means invalid current measurement
_discharged_mah_loop = (current_a * 1e3f) * (_dt / 3600.f);
_discharged_mah += _discharged_mah_loop;
}
return _discharged_mah;
}
float Battery::calculateStateOfChargeVoltageBased(const float voltage_v, const float current_a)
{
if (_params.n_cells == 0) {
return -1.0f;
}
// remaining battery capacity based on voltage
float cell_voltage = voltage_v / _params.n_cells;
// correct battery voltage locally for load drop according to internal resistance and current
if (current_a > FLT_EPSILON) {
updateInternalResistanceEstimation(voltage_v, current_a);
if (_params.r_internal >= 0.f) { // Use user specified internal resistance value
cell_voltage += _params.r_internal * current_a;
} else { // Use estimated internal resistance value
cell_voltage += _internal_resistance_estimate * current_a;
}
}
_cell_voltage_filter_v.update(cell_voltage);
return math::interpolate(_cell_voltage_filter_v.getState(), _params.v_empty, _params.v_charged, 0.f, 1.f);
}
void Battery::updateInternalResistanceEstimation(const float voltage_v, const float current_a)
{
Vector2f x{1, -current_a};
_voltage_prediction = (x.transpose() * _RLS_est)(0, 0);
_prediction_error = voltage_v - _voltage_prediction;
const Vector2f gamma = _estimation_covariance * x / (LAMBDA + (x.transpose() * _estimation_covariance * x)(0, 0));
const Vector2f RSL_est_temp = _RLS_est + gamma * _prediction_error;
const Matrix2f estimation_covariance_temp = (_estimation_covariance
- Matrix<float, 2, 1>(gamma) * (x.transpose() * _estimation_covariance)) / LAMBDA;
const float estimation_covariance_temp_norm =
sqrtf(powf(estimation_covariance_temp(0, 0), 2.f)
+ 2.f * powf(estimation_covariance_temp(1, 0), 2.f)
+ powf(estimation_covariance_temp(1, 1), 2.f));
if (estimation_covariance_temp_norm < _estimation_covariance_norm) { // Only update if estimation improves
_RLS_est = RSL_est_temp;
_estimation_covariance = estimation_covariance_temp;
_estimation_covariance_norm = estimation_covariance_temp_norm;
_internal_resistance_estimate =
math::max(_RLS_est(1) / _params.n_cells, 0.f); // Only use positive values
} else { // Update OCV estimate with IR estimate
_RLS_est(0) = voltage_v + _RLS_est(1) * current_a;
}
_ocv_filter_v.update(voltage_v + _internal_resistance_estimate * _params.n_cells * current_a);
}
void Battery::resetInternalResistanceEstimation(const float voltage_v, const float current_a)
{
_RLS_est(0) = voltage_v;
_RLS_est(1) = R_DEFAULT * _params.n_cells;
_estimation_covariance.setZero();
_estimation_covariance(0, 0) = OCV_COVARIANCE * _params.n_cells;
_estimation_covariance(1, 1) = R_COVARIANCE * _params.n_cells;
_estimation_covariance_norm = sqrtf(powf(_estimation_covariance(0, 0), 2.f) + 2.f * powf(_estimation_covariance(1, 0),
2.f) + powf(_estimation_covariance(1, 1), 2.f));
_internal_resistance_estimate = R_DEFAULT;
_ocv_filter_v.reset(voltage_v + _internal_resistance_estimate * _params.n_cells * current_a);
if (_params.r_internal >= 0.f) { // Use user specified internal resistance value
_cell_voltage_filter_v.reset(voltage_v / _params.n_cells + _params.r_internal * current_a);
} else { // Use estimated internal resistance value
_cell_voltage_filter_v.reset(voltage_v / _params.n_cells + _internal_resistance_estimate * current_a);
}
}
void Battery::estimateStateOfCharge()
{
// choose which quantity we're using for final reporting
if ((_capacity_mah > 0.f) && _battery_initialized) {
// if battery capacity is known, fuse voltage measurement with used capacity
// The lower the voltage the more adjust the estimate with it to avoid deep discharge
const float weight_v = 3e-2f * (1 - _state_of_charge_volt_based);
_state_of_charge = (1 - weight_v) * _state_of_charge + weight_v * _state_of_charge_volt_based;
// directly apply current capacity slope calculated using current
_state_of_charge -= _discharged_mah_loop / _capacity_mah;
_state_of_charge = math::max(_state_of_charge, 0.f);
const float state_of_charge_current_based = math::max(1.f - _discharged_mah / _capacity_mah, 0.f);
_state_of_charge = math::min(state_of_charge_current_based, _state_of_charge);
} else {
_state_of_charge = _state_of_charge_volt_based;
}
}
uint8_t Battery::determineWarning(float state_of_charge)
{
if (state_of_charge < _params.emergen_thr) {
return battery_status_s::WARNING_EMERGENCY;
} else if (state_of_charge < _params.crit_thr) {
return battery_status_s::WARNING_CRITICAL;
} else if (state_of_charge < _params.low_thr) {
return battery_status_s::WARNING_LOW;
} else {
return battery_status_s::WARNING_NONE;
}
}
uint16_t Battery::determineFaults()
{
uint16_t faults{0};
if ((_params.n_cells > 0)
&& (_voltage_v > (_params.n_cells * _params.v_charged * 1.05f))) {
// Reported as a "spike" since "over-voltage" does not exist in MAV_BATTERY_FAULT
faults |= (1 << battery_status_s::FAULT_SPIKES);
}
if (PX4_ISFINITE(_temperature_c) && _temperature_c > BAT_TEMP_MAX) {
faults |= (1 << battery_status_s::FAULT_OVER_TEMPERATURE);
}
return faults;
}
void Battery::computeScale()
{
_scale = _params.v_charged / _cell_voltage_filter_v.getState();
if (PX4_ISFINITE(_scale)) {
_scale = math::constrain(_scale, 1.f, 1.3f); // Allow at most 30% compensation
} else {
_scale = 1.f;
}
}
float Battery::computeRemainingTime(float current_a)
{
float time_remaining_s = NAN;
_flight_phase_estimation_sub.update();
bool reset_filter_transition_now = !_vehicle_status_was_fw && _vehicle_status_is_fw;
// reset filter if not feasible, negative or we did a VTOL transition to FW mode
if (!PX4_ISFINITE(_current_average_filter_a.getState()) || _current_average_filter_a.getState() < FLT_EPSILON
|| reset_filter_transition_now) {
_current_average_filter_a.reset(_params.bat_avrg_current);
}
_vehicle_status_was_fw = _vehicle_status_is_fw;
if (_armed && PX4_ISFINITE(current_a)) {
// For FW only update when we are in level flight
if (!_vehicle_status_is_fw || ((hrt_absolute_time() - _flight_phase_estimation_sub.get().timestamp) < 2_s
&& _flight_phase_estimation_sub.get().flight_phase == flight_phase_estimation_s::FLIGHT_PHASE_LEVEL)) {
if (_dt > FLT_EPSILON) {
_current_average_filter_a.update(fmaxf(current_a, 0.f), _dt);
} else {
_current_average_filter_a.update(fmaxf(current_a, 0.f));
}
}
}
// Remaining time estimation only possible with capacity
if (_capacity_mah > 0.f) {
const float remaining_capacity_mah = _state_of_charge * _capacity_mah;
const float current_ma = fmaxf(_current_average_filter_a.getState() * 1e3f, FLT_EPSILON);
time_remaining_s = remaining_capacity_mah / current_ma * 3600.f;
}
return time_remaining_s;
}
void Battery::updateParams()
{
const int n_cells = _first_parameter_update ? 0 : _params.n_cells;
param_get(_param_handles.v_empty, &_params.v_empty);
param_get(_param_handles.v_charged, &_params.v_charged);
param_get(_param_handles.n_cells, &_params.n_cells);
param_get(_param_handles.r_internal, &_params.r_internal);
param_get(_param_handles.source, &_params.source);
param_get(_param_handles.low_thr, &_params.low_thr);
param_get(_param_handles.crit_thr, &_params.crit_thr);
param_get(_param_handles.emergen_thr, &_params.emergen_thr);
param_get(_param_handles.bat_avrg_current, &_params.bat_avrg_current);
param_get(_param_handles.i_overwrite, &_params.i_overwrite);
float capacity{0.f};
param_get(_param_handles.capacity, &capacity);
setCapacityMah(capacity);
if (n_cells != _params.n_cells) {
_internal_resistance_initialized = false;
}
if (!_internal_resistance_initialized && _params.n_cells > 0) {
_RLS_est(0) = OCV_DEFAULT * _params.n_cells;
_RLS_est(1) = R_DEFAULT * _params.n_cells;
_estimation_covariance(0, 0) = OCV_COVARIANCE * _params.n_cells;
_estimation_covariance(0, 1) = 0.f;
_estimation_covariance(1, 0) = 0.f;
_estimation_covariance(1, 1) = R_COVARIANCE * _params.n_cells;
_estimation_covariance_norm = sqrtf(powf(_estimation_covariance(0, 0), 2.f) + 2.f * powf(_estimation_covariance(1, 0),
2.f) + powf(_estimation_covariance(1, 1), 2.f));
_internal_resistance_initialized = true;
}
ModuleParams::updateParams();
_first_parameter_update = false;
}