Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/AP_Periph/battery_bms.cpp
9424 views
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
battery BMS includes a button which, when pressed, shows the state of charge percentage using LEDs
17
*/
18
#include "AP_Periph.h"
19
20
#if AP_PERIPH_BATTERY_BMS_ENABLED
21
#include "stdio.h"
22
#include "battery_bms.h"
23
24
extern const AP_HAL::HAL &hal;
25
extern AP_Periph_FW periph;
26
27
// GPIO pins used for BMS LEDs
28
const uint8_t BatteryBMS::led_gpios[] = {AP_PERIPH_BMS_LED_PINS};
29
30
// configure gpio pins. returns true once configured
31
bool BatteryBMS::configured()
32
{
33
if (config_complete) {
34
return true;
35
}
36
37
// when HAL_GPIO_LED_ON is 0 then we must not use pinMode()
38
// as it could remove the OPENDRAIN attribute on the pin
39
// configure LED pins as outputs
40
#if HAL_GPIO_LED_ON != 0
41
for (uint8_t i = 0; i < ARRAY_SIZE(led_gpios); i++) {
42
hal.gpio->pinMode(led_gpios[i], HAL_GPIO_OUTPUT);
43
}
44
#endif
45
46
// configure button as input with pullup
47
#ifdef HAL_GPIO_PIN_BMS_BTN1
48
hal.gpio->pinMode(HAL_GPIO_PIN_BMS_BTN1, HAL_GPIO_INPUT);
49
hal.gpio->write(HAL_GPIO_PIN_BMS_BTN1, 1);
50
#endif
51
52
// mark configuration as complete
53
config_complete = true;
54
return true;
55
}
56
57
// main update function
58
void BatteryBMS::update(void)
59
{
60
// exit immediately if no batteries are enabled
61
if (periph.battery_lib.num_instances() == 0) {
62
return;
63
}
64
65
// configure
66
if (!configured()) {
67
return;
68
}
69
70
#ifdef HAL_GPIO_PIN_BMS_BTN1
71
// check and handle button press events
72
handle_button_press();
73
#endif
74
75
// update BMS state machine
76
update_bms_state();
77
78
// update LED state machine
79
update_led_state();
80
}
81
82
// check and handle button press events
83
void BatteryBMS::handle_button_press(void)
84
{
85
// we take action in these cases
86
// 1. button is released after being pressed between 10ms an 1 sec, we display the battery percentage (short press)
87
// 2. button is pressed for at least 1 second (long press), we start the power-up or power-down counter and animation
88
// 3. button is released after case 2 but before the counter and animation has completed, we cancel the power-up or power-down action
89
// 4. button is released after the power-up or power-down counter and animation have completed, no further action is taken
90
91
// ignore button presses during startup to avoid false detections from GPIO initialization
92
uint32_t now_ms = AP_HAL::millis();
93
if (!button.startup_complete && (now_ms < BUTTON_STARTUP_DELAY_MS)) {
94
return;
95
}
96
button.startup_complete = true;
97
98
// read current button state (assuming active low - pressed = 0)
99
bool button_pressed = (hal.gpio->read(HAL_GPIO_PIN_BMS_BTN1) == 0);
100
101
// check if button has just been pressed (transition from released to pressed)
102
if (button_pressed && !button.pressed_prev) {
103
// record time button was pressed
104
button.pressed_start_ms = now_ms;
105
106
// record button pressed state before returning
107
button.pressed_prev = button_pressed;
108
button.long_press_handled = false;
109
return;
110
}
111
112
// calculate how long the button was pressed including when button has just been released
113
const uint32_t press_duration_ms = (button_pressed || button.pressed_prev) ? (now_ms - button.pressed_start_ms) : 0;
114
const bool short_press = (press_duration_ms > BUTTON_SHORT_PRESS_THRESHOLD_MS) && (press_duration_ms < BUTTON_LONG_PRESS_THRESHOLD_MS);
115
const bool long_press = (press_duration_ms >= BUTTON_LONG_PRESS_THRESHOLD_MS);
116
117
// check if button has just been released (transition from pressed to released)
118
bool button_released = false;
119
if (!button_pressed && button.pressed_prev) {
120
button.pressed_start_ms = 0;
121
button_released = true;
122
}
123
124
// update button state for next iteration
125
button.pressed_prev = button_pressed;
126
127
// handle release after short press
128
// displays battery SOC percentage on LEDs and prints voltages to the console
129
if (short_press && button_released) {
130
request_display_percentage();
131
return;
132
}
133
134
// handle long press event
135
// starts power on/off sequence
136
if (long_press && !button.long_press_handled) {
137
138
// ensure we only handle long press once
139
button.long_press_handled = true;
140
141
switch (bms_state) {
142
case BmsState::IDLE:
143
case BmsState::POWERING_OFF:
144
case BmsState::POWERED_OFF:
145
// if battery is off, request power on
146
request_bms_state(BmsState::POWERED_ON);
147
break;
148
case BmsState::POWERING_ON:
149
case BmsState::POWERED_ON:
150
// if battery if on, request power off
151
request_bms_state(BmsState::POWERED_OFF);
152
break;
153
}
154
return;
155
}
156
157
// handle release after long press
158
if (long_press && button_released) {
159
// if the BMS is transitioning to powered on or off, abort the transition
160
switch (bms_state) {
161
case BmsState::POWERING_ON:
162
// request power off
163
request_bms_state(BmsState::POWERED_OFF);
164
break;
165
case BmsState::POWERING_OFF:
166
request_bms_state(BmsState::POWERED_ON);
167
break;
168
case BmsState::IDLE:
169
case BmsState::POWERED_ON:
170
case BmsState::POWERED_OFF:
171
// BMS/battery have already completed the power on/off action -- do nothing
172
break;
173
}
174
return;
175
}
176
}
177
178
// request display of battery percentage using LEDs
179
void BatteryBMS::request_display_percentage()
180
{
181
led_display_soc_start_ms = AP_HAL::millis();
182
}
183
184
// display battery SOC percentage using LEDs
185
void BatteryBMS::display_percentage()
186
{
187
// get battery percentage
188
uint8_t batt_soc_pct;
189
if (!get_percentage(batt_soc_pct)) {
190
return;
191
}
192
193
// calculate how many LEDs to light up based on battery percentage
194
// uses ceiling division to round up: 0% = 0 LEDs, 1-12% = 1 LED, etc
195
const uint8_t num_leds = ARRAY_SIZE(led_gpios);
196
const uint8_t num_leds_on = MIN(num_leds, (batt_soc_pct * num_leds + 99) / 100);
197
198
// build bitmask for LEDs (e.g., num_leds=3 gives 0b00000111)
199
const uint8_t pattern = (1U << num_leds_on) - 1;
200
201
// set the LED pattern and start display timer
202
set_led_pattern(pattern);
203
}
204
205
// get battery percentage (0-100). returns true on success
206
bool BatteryBMS::get_percentage(uint8_t &percentage)
207
{
208
percentage = 0;
209
210
// try to get capacity remaining percentage first
211
if (periph.battery_lib.capacity_remaining_pct(percentage, 0)) {
212
return true;
213
}
214
215
// fallback: calculate percentage from average cell voltage
216
// Li-ion/LiPo typical range: 3.0V (0%) to 4.2V (100%)
217
if (!periph.battery_lib.has_cell_voltages()) {
218
return false;
219
}
220
const AP_BattMonitor::cells &cell_voltages = periph.battery_lib.get_cell_voltages();
221
uint32_t total_voltage_mv = 0;
222
uint8_t cell_count = 0;
223
224
for (uint8_t i = 0; i < ARRAY_SIZE(cell_voltages.cells); i++) {
225
if (cell_voltages.cells[i] == UINT16_MAX) {
226
break;
227
}
228
total_voltage_mv += cell_voltages.cells[i];
229
cell_count++;
230
}
231
232
if (cell_count > 0) {
233
uint16_t avg_cell_voltage_mv = total_voltage_mv / cell_count;
234
// map 3000mV-4200mV to 0-100%
235
if (avg_cell_voltage_mv <= 3000) {
236
percentage = 0;
237
} else if (avg_cell_voltage_mv >= 4200) {
238
percentage = 100;
239
} else {
240
percentage = constrain_uint16((avg_cell_voltage_mv - 3000) * 100 / 1200, 0, 100);
241
}
242
return true;
243
}
244
245
return false;
246
}
247
248
// set LED pattern based on 8-bit bitmask
249
void BatteryBMS::set_led_pattern(uint8_t pattern)
250
{
251
// configure LED pins as outputs
252
for (uint8_t i = 0; i < ARRAY_SIZE(led_gpios); i++) {
253
hal.gpio->write(led_gpios[i], BIT_IS_SET(pattern, i) ? HAL_GPIO_LED_ON : HAL_GPIO_LED_OFF);
254
}
255
}
256
257
// LED state machine - manages LED display based on battery state
258
void BatteryBMS::update_led_state(void)
259
{
260
// slow down LED updates
261
const uint32_t now_ms = AP_HAL::millis();
262
if (now_ms - led_last_update_ms < LED_UPDATE_INTERVAL_MS) {
263
return;
264
}
265
led_last_update_ms = now_ms;
266
267
// display state-of-charge (SOC) percentage
268
if (led_display_soc_start_ms > 0) {
269
// display SOC percentage
270
display_percentage();
271
272
// turn off SOC display after 1 second
273
if (now_ms - led_display_soc_start_ms >= LED_DISPLAY_SOC_DURATION_MS) {
274
led_display_soc_start_ms = 0;
275
}
276
return;
277
}
278
279
// handle POWERING_ON / OFF transition
280
if (bms_state == BmsState::POWERING_ON || bms_state == BmsState::POWERING_OFF) {
281
// turn on LEDs sequentially
282
set_led_pattern((1 << bms_transition_counter) - 1);
283
return;
284
}
285
286
// run animation while charging
287
auto battery_charging_state = periph.battery_lib.get_charging_state();
288
if (battery_charging_state == AP_BattMonitor::ChargingState::CHARGING) {
289
led_charging_animation_step = (led_charging_animation_step + 1) % 8;
290
291
// charging: chase forward (bit 0 -> 7)
292
uint8_t pattern = 1 << led_charging_animation_step;
293
set_led_pattern(pattern);
294
return;
295
}
296
297
// handle POWERED_ON state - display SOC percentage
298
if (bms_state == BmsState::POWERED_ON) {
299
display_percentage();
300
return;
301
}
302
303
// if we get this far, turn all LEDs off
304
set_led_pattern(0x00);
305
}
306
307
// set bms state. the only valid inputs are POWERED_ON and POWERING_OFF
308
// return true on success
309
bool BatteryBMS::request_bms_state(BmsState new_state)
310
{
311
// sanity check inputs
312
if (new_state != BmsState::POWERED_ON && new_state != BmsState::POWERED_OFF) {
313
return false;
314
}
315
316
// if request is already in progress then return true
317
if (req_bms_state == new_state) {
318
return true;
319
}
320
321
// handle request to power on the battery
322
if (new_state == BmsState::POWERED_ON) {
323
// allow cancelling a power-off transition
324
if (bms_state == BmsState::POWERING_OFF) {
325
req_bms_state = new_state;
326
return true;
327
}
328
// allow power on when battery is in IDLE state
329
if (periph.battery_lib.get_charging_state() == AP_BattMonitor::ChargingState::IDLE) {
330
req_bms_state = new_state;
331
return true;
332
}
333
return false;
334
}
335
336
// always accept request to power off the battery
337
req_bms_state = new_state;
338
return true;
339
}
340
341
// update bms state. transitions bms_state to req_bms_state
342
void BatteryBMS::update_bms_state()
343
{
344
// return immediately if current state matches requested state or requested state is IDLE
345
if (bms_state == req_bms_state || req_bms_state == BmsState::IDLE) {
346
return;
347
}
348
349
// rate limit state transitions to match LED update interval (~1.2 seconds for full animation)
350
uint32_t now_ms = AP_HAL::millis();
351
if (now_ms - bms_last_update_ms < LED_UPDATE_INTERVAL_MS) {
352
return;
353
}
354
bms_last_update_ms = now_ms;
355
356
// handle request to power on
357
if (req_bms_state == BmsState::POWERED_ON) {
358
switch (bms_state) {
359
case BmsState::IDLE:
360
case BmsState::POWERING_OFF:
361
case BmsState::POWERED_OFF:
362
// move to powering on
363
bms_state = BmsState::POWERING_ON;
364
bms_transition_counter = 0;
365
break;
366
case BmsState::POWERING_ON:
367
bms_transition_counter++;
368
if (bms_transition_counter >= 8) {
369
bms_state = BmsState::POWERED_ON;
370
bms_transition_counter = 0;
371
periph.battery_lib.set_powered_state(0, true);
372
}
373
break;
374
case BmsState::POWERED_ON:
375
// already powered on -- do nothing
376
break;
377
}
378
return;
379
}
380
381
// handle request to power off
382
if (req_bms_state == BmsState::POWERED_OFF) {
383
switch (bms_state) {
384
case BmsState::IDLE:
385
case BmsState::POWERED_OFF:
386
// already powered off -- do nothing
387
break;
388
case BmsState::POWERED_ON:
389
// move to powering off state
390
bms_transition_counter = 8;
391
bms_state = BmsState::POWERING_OFF;
392
break;
393
case BmsState::POWERING_ON:
394
// move to powering off state. transition counter should already be between 0 and 8
395
bms_state = BmsState::POWERING_OFF;
396
break;
397
case BmsState::POWERING_OFF:
398
if (bms_transition_counter > 0) {
399
bms_transition_counter--;
400
}
401
if (bms_transition_counter == 0) {
402
bms_state = BmsState::POWERED_OFF;
403
periph.battery_lib.set_powered_state(0, false);
404
}
405
break;
406
}
407
return;
408
}
409
}
410
411
#endif // AP_PERIPH_BATTERY_BMS_ENABLED
412
413