#include "AP_Periph.h"
#if AP_PERIPH_BATTERY_BMS_ENABLED
#include "stdio.h"
#include "battery_bms.h"
extern const AP_HAL::HAL &hal;
extern AP_Periph_FW periph;
const uint8_t BatteryBMS::led_gpios[] = {AP_PERIPH_BMS_LED_PINS};
bool BatteryBMS::configured()
{
if (config_complete) {
return true;
}
#if HAL_GPIO_LED_ON != 0
for (uint8_t i = 0; i < ARRAY_SIZE(led_gpios); i++) {
hal.gpio->pinMode(led_gpios[i], HAL_GPIO_OUTPUT);
}
#endif
#ifdef HAL_GPIO_PIN_BMS_BTN1
hal.gpio->pinMode(HAL_GPIO_PIN_BMS_BTN1, HAL_GPIO_INPUT);
hal.gpio->write(HAL_GPIO_PIN_BMS_BTN1, 1);
#endif
config_complete = true;
return true;
}
void BatteryBMS::update(void)
{
if (periph.battery_lib.num_instances() == 0) {
return;
}
if (!configured()) {
return;
}
#ifdef HAL_GPIO_PIN_BMS_BTN1
handle_button_press();
#endif
update_bms_state();
update_led_state();
}
void BatteryBMS::handle_button_press(void)
{
uint32_t now_ms = AP_HAL::millis();
if (!button.startup_complete && (now_ms < BUTTON_STARTUP_DELAY_MS)) {
return;
}
button.startup_complete = true;
bool button_pressed = (hal.gpio->read(HAL_GPIO_PIN_BMS_BTN1) == 0);
if (button_pressed && !button.pressed_prev) {
button.pressed_start_ms = now_ms;
button.pressed_prev = button_pressed;
button.long_press_handled = false;
return;
}
const uint32_t press_duration_ms = (button_pressed || button.pressed_prev) ? (now_ms - button.pressed_start_ms) : 0;
const bool short_press = (press_duration_ms > BUTTON_SHORT_PRESS_THRESHOLD_MS) && (press_duration_ms < BUTTON_LONG_PRESS_THRESHOLD_MS);
const bool long_press = (press_duration_ms >= BUTTON_LONG_PRESS_THRESHOLD_MS);
bool button_released = false;
if (!button_pressed && button.pressed_prev) {
button.pressed_start_ms = 0;
button_released = true;
}
button.pressed_prev = button_pressed;
if (short_press && button_released) {
request_display_percentage();
return;
}
if (long_press && !button.long_press_handled) {
button.long_press_handled = true;
switch (bms_state) {
case BmsState::IDLE:
case BmsState::POWERING_OFF:
case BmsState::POWERED_OFF:
request_bms_state(BmsState::POWERED_ON);
break;
case BmsState::POWERING_ON:
case BmsState::POWERED_ON:
request_bms_state(BmsState::POWERED_OFF);
break;
}
return;
}
if (long_press && button_released) {
switch (bms_state) {
case BmsState::POWERING_ON:
request_bms_state(BmsState::POWERED_OFF);
break;
case BmsState::POWERING_OFF:
request_bms_state(BmsState::POWERED_ON);
break;
case BmsState::IDLE:
case BmsState::POWERED_ON:
case BmsState::POWERED_OFF:
break;
}
return;
}
}
void BatteryBMS::request_display_percentage()
{
led_display_soc_start_ms = AP_HAL::millis();
}
void BatteryBMS::display_percentage()
{
uint8_t batt_soc_pct;
if (!get_percentage(batt_soc_pct)) {
return;
}
const uint8_t num_leds = ARRAY_SIZE(led_gpios);
const uint8_t num_leds_on = MIN(num_leds, (batt_soc_pct * num_leds + 99) / 100);
const uint8_t pattern = (1U << num_leds_on) - 1;
set_led_pattern(pattern);
}
bool BatteryBMS::get_percentage(uint8_t &percentage)
{
percentage = 0;
if (periph.battery_lib.capacity_remaining_pct(percentage, 0)) {
return true;
}
if (!periph.battery_lib.has_cell_voltages()) {
return false;
}
const AP_BattMonitor::cells &cell_voltages = periph.battery_lib.get_cell_voltages();
uint32_t total_voltage_mv = 0;
uint8_t cell_count = 0;
for (uint8_t i = 0; i < ARRAY_SIZE(cell_voltages.cells); i++) {
if (cell_voltages.cells[i] == UINT16_MAX) {
break;
}
total_voltage_mv += cell_voltages.cells[i];
cell_count++;
}
if (cell_count > 0) {
uint16_t avg_cell_voltage_mv = total_voltage_mv / cell_count;
if (avg_cell_voltage_mv <= 3000) {
percentage = 0;
} else if (avg_cell_voltage_mv >= 4200) {
percentage = 100;
} else {
percentage = constrain_uint16((avg_cell_voltage_mv - 3000) * 100 / 1200, 0, 100);
}
return true;
}
return false;
}
void BatteryBMS::set_led_pattern(uint8_t pattern)
{
for (uint8_t i = 0; i < ARRAY_SIZE(led_gpios); i++) {
hal.gpio->write(led_gpios[i], BIT_IS_SET(pattern, i) ? HAL_GPIO_LED_ON : HAL_GPIO_LED_OFF);
}
}
void BatteryBMS::update_led_state(void)
{
const uint32_t now_ms = AP_HAL::millis();
if (now_ms - led_last_update_ms < LED_UPDATE_INTERVAL_MS) {
return;
}
led_last_update_ms = now_ms;
if (led_display_soc_start_ms > 0) {
display_percentage();
if (now_ms - led_display_soc_start_ms >= LED_DISPLAY_SOC_DURATION_MS) {
led_display_soc_start_ms = 0;
}
return;
}
if (bms_state == BmsState::POWERING_ON || bms_state == BmsState::POWERING_OFF) {
set_led_pattern((1 << bms_transition_counter) - 1);
return;
}
auto battery_charging_state = periph.battery_lib.get_charging_state();
if (battery_charging_state == AP_BattMonitor::ChargingState::CHARGING) {
led_charging_animation_step = (led_charging_animation_step + 1) % 8;
uint8_t pattern = 1 << led_charging_animation_step;
set_led_pattern(pattern);
return;
}
if (bms_state == BmsState::POWERED_ON) {
display_percentage();
return;
}
set_led_pattern(0x00);
}
bool BatteryBMS::request_bms_state(BmsState new_state)
{
if (new_state != BmsState::POWERED_ON && new_state != BmsState::POWERED_OFF) {
return false;
}
if (req_bms_state == new_state) {
return true;
}
if (new_state == BmsState::POWERED_ON) {
if (bms_state == BmsState::POWERING_OFF) {
req_bms_state = new_state;
return true;
}
if (periph.battery_lib.get_charging_state() == AP_BattMonitor::ChargingState::IDLE) {
req_bms_state = new_state;
return true;
}
return false;
}
req_bms_state = new_state;
return true;
}
void BatteryBMS::update_bms_state()
{
if (bms_state == req_bms_state || req_bms_state == BmsState::IDLE) {
return;
}
uint32_t now_ms = AP_HAL::millis();
if (now_ms - bms_last_update_ms < LED_UPDATE_INTERVAL_MS) {
return;
}
bms_last_update_ms = now_ms;
if (req_bms_state == BmsState::POWERED_ON) {
switch (bms_state) {
case BmsState::IDLE:
case BmsState::POWERING_OFF:
case BmsState::POWERED_OFF:
bms_state = BmsState::POWERING_ON;
bms_transition_counter = 0;
break;
case BmsState::POWERING_ON:
bms_transition_counter++;
if (bms_transition_counter >= 8) {
bms_state = BmsState::POWERED_ON;
bms_transition_counter = 0;
periph.battery_lib.set_powered_state(0, true);
}
break;
case BmsState::POWERED_ON:
break;
}
return;
}
if (req_bms_state == BmsState::POWERED_OFF) {
switch (bms_state) {
case BmsState::IDLE:
case BmsState::POWERED_OFF:
break;
case BmsState::POWERED_ON:
bms_transition_counter = 8;
bms_state = BmsState::POWERING_OFF;
break;
case BmsState::POWERING_ON:
bms_state = BmsState::POWERING_OFF;
break;
case BmsState::POWERING_OFF:
if (bms_transition_counter > 0) {
bms_transition_counter--;
}
if (bms_transition_counter == 0) {
bms_state = BmsState::POWERED_OFF;
periph.battery_lib.set_powered_state(0, false);
}
break;
}
return;
}
}
#endif