1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 16:25:31 +03:00

Add BATT NOT FULL warning to OSD

Shows BATT NOT FULL when the connected battery has an everage cell
voltage of less than 0.2v lower then vbatmaxcellvoltage (when the craft
has yet to be armed)

Intended as a reminder to make sure pilots fly with a fresh battery

Adds an additional configuration option for the voltage at which a cell
is "full"
This commit is contained in:
Dan Nixon 2017-08-17 11:42:26 +01:00
parent 27b146e274
commit 20f7c77089
5 changed files with 101 additions and 1 deletions

View file

@ -426,6 +426,7 @@ const clivalue_t valueTable[] = {
// PG_BATTERY_CONFIG
{ "bat_capacity", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 20000 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, batteryCapacity) },
{ "vbat_max_cell_voltage", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 10, 50 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbatmaxcellvoltage) },
{ "vbat_full_cell_voltage", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 10, 50 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbatfullcellvoltage) },
{ "vbat_min_cell_voltage", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 10, 50 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbatmincellvoltage) },
{ "vbat_warning_cell_voltage", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 10, 50 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbatwarningcellvoltage) },
{ "vbat_hysteresis", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 250 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbathysteresis) },

View file

@ -596,6 +596,13 @@ static void osdDrawSingleElement(uint8_t item)
break;
}
/* Show warning if battery is not fresh */
if (!ARMING_FLAG(WAS_EVER_ARMED) && (getBatteryState() == BATTERY_OK)
&& getBatteryAverageCellVoltage() < batteryConfig()->vbatfullcellvoltage) {
tfp_sprintf(buff, "BATT NOT FULL");
break;
}
/* Show battery state warning */
switch (getBatteryState()) {
case BATTERY_WARNING:

View file

@ -106,7 +106,9 @@ PG_RESET_TEMPLATE(batteryConfig_t, batteryConfig,
.useVBatAlerts = true,
.useConsumptionAlerts = false,
.consumptionWarningPercentage = 10,
.vbathysteresis = 1
.vbathysteresis = 1,
.vbatfullcellvoltage = 41
);
void batteryUpdateVoltage(timeUs_t currentTimeUs)
@ -462,6 +464,11 @@ uint8_t getBatteryCellCount(void)
return batteryCellCount;
}
uint16_t getBatteryAverageCellVoltage(void)
{
return voltageMeter.filtered / batteryCellCount;
}
int32_t getAmperage(void) {
return currentMeter.amperage;
}

View file

@ -42,6 +42,8 @@ typedef struct batteryConfig_s {
bool useConsumptionAlerts; // Issue alerts based on total power consumption
uint8_t consumptionWarningPercentage; // Percentage of remaining capacity that should trigger a battery warning
uint8_t vbathysteresis; // hysteresis for alarm, default 1 = 0.1V
uint8_t vbatfullcellvoltage; // Cell voltage at which the battery is deemed to be "full" 0.1V units, default is 41 (4.1V)
} batteryConfig_t;
@ -77,6 +79,7 @@ uint8_t calculateBatteryPercentageRemaining(void);
uint16_t getBatteryVoltage(void);
uint16_t getBatteryVoltageLatest(void);
uint8_t getBatteryCellCount(void);
uint16_t getBatteryAverageCellVoltage(void);
int32_t getAmperage(void);
int32_t getAmperageLatest(void);

View file

@ -648,6 +648,84 @@ TEST(OsdTest, TestElementAltitude)
displayPortTestBufferSubstring(23, 7, " -2.4%c", SYM_M);
}
/*
* Tests the battery notifications shown on the warnings OSD element.
*/
TEST(OsdTest, TestElementWarningsBattery)
{
// given
osdConfigMutable()->item_pos[OSD_WARNINGS] = OSD_POS(9, 10) | VISIBLE_FLAG;
// and
batteryConfigMutable()->vbatfullcellvoltage = 41;
// and
// 4S battery
simulationBatteryCellCount = 4;
// and
// full battery
simulationBatteryVoltage = 168;
simulationBatteryState = BATTERY_OK;
// when
displayClearScreen(&testDisplayPort);
osdRefresh(simulationTime);
// then
displayPortTestBufferSubstring(9, 10, " ");
// given
// low battery
simulationBatteryVoltage = 140;
simulationBatteryState = BATTERY_WARNING;
// when
displayClearScreen(&testDisplayPort);
osdRefresh(simulationTime);
// then
displayPortTestBufferSubstring(9, 10, "LOW BATTERY ");
// given
// crtical battery
simulationBatteryVoltage = 132;
simulationBatteryState = BATTERY_CRITICAL;
// when
displayClearScreen(&testDisplayPort);
osdRefresh(simulationTime);
// then
displayPortTestBufferSubstring(9, 10, " LAND NOW ");
// given
// used battery
simulationBatteryVoltage = ((batteryConfig()->vbatmaxcellvoltage - 2) * simulationBatteryCellCount) - 1;
simulationBatteryState = BATTERY_OK;
// when
displayClearScreen(&testDisplayPort);
osdRefresh(simulationTime);
// then
displayPortTestBufferSubstring(9, 10, "BATT NOT FULL");
// given
// full battery
simulationBatteryVoltage = ((batteryConfig()->vbatmaxcellvoltage - 2) * simulationBatteryCellCount);
simulationBatteryState = BATTERY_OK;
// when
displayClearScreen(&testDisplayPort);
osdRefresh(simulationTime);
// then
displayPortTestBufferSubstring(9, 10, " ");
// TODO
}
/*
* Tests the time string formatting function with a series of precision settings and time values.
*/
@ -744,6 +822,10 @@ extern "C" {
return simulationBatteryVoltage;
}
uint16_t getBatteryAverageCellVoltage() {
return simulationBatteryVoltage / simulationBatteryCellCount;
}
int32_t getAmperage() {
return simulationBatteryAmperage;
}