mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-21 07:15:18 +03:00
add way to manually override battery cell count
This commit is contained in:
parent
793c5f7b71
commit
3fea35079f
8 changed files with 24 additions and 1 deletions
|
@ -654,6 +654,7 @@ static bool mspCommonProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProce
|
||||||
sbufWriteU16(dst, batteryConfig()->batteryCapacity);
|
sbufWriteU16(dst, batteryConfig()->batteryCapacity);
|
||||||
sbufWriteU8(dst, batteryConfig()->voltageMeterSource);
|
sbufWriteU8(dst, batteryConfig()->voltageMeterSource);
|
||||||
sbufWriteU8(dst, batteryConfig()->currentMeterSource);
|
sbufWriteU8(dst, batteryConfig()->currentMeterSource);
|
||||||
|
sbufWriteU8(dst, batteryConfig()->setBatteryCellCount);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_TRANSPONDER_CONFIG: {
|
case MSP_TRANSPONDER_CONFIG: {
|
||||||
|
@ -2418,6 +2419,7 @@ static mspResult_e mspCommonProcessInCommand(uint8_t cmdMSP, sbuf_t *src, mspPos
|
||||||
batteryConfigMutable()->batteryCapacity = sbufReadU16(src);
|
batteryConfigMutable()->batteryCapacity = sbufReadU16(src);
|
||||||
batteryConfigMutable()->voltageMeterSource = sbufReadU8(src);
|
batteryConfigMutable()->voltageMeterSource = sbufReadU8(src);
|
||||||
batteryConfigMutable()->currentMeterSource = sbufReadU8(src);
|
batteryConfigMutable()->currentMeterSource = sbufReadU8(src);
|
||||||
|
batteryConfigMutable()->setBatteryCellCount = sbufReadU8(src);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#if defined(USE_OSD)
|
#if defined(USE_OSD)
|
||||||
|
|
|
@ -682,6 +682,7 @@ const clivalue_t valueTable[] = {
|
||||||
{ "use_cbat_alerts", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, useConsumptionAlerts) },
|
{ "use_cbat_alerts", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, useConsumptionAlerts) },
|
||||||
{ "cbat_alert_percent", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, consumptionWarningPercentage) },
|
{ "cbat_alert_percent", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, consumptionWarningPercentage) },
|
||||||
{ "vbat_cutoff_percent", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, lvcPercentage) },
|
{ "vbat_cutoff_percent", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, lvcPercentage) },
|
||||||
|
{ "set_battery_cell_count", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 10, 80 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, setBatteryCellCount) },
|
||||||
|
|
||||||
// PG_VOLTAGE_SENSOR_ADC_CONFIG
|
// PG_VOLTAGE_SENSOR_ADC_CONFIG
|
||||||
{ "vbat_scale", VAR_UINT8 | MASTER_VALUE, .config.minmax = { VBAT_SCALE_MIN, VBAT_SCALE_MAX }, PG_VOLTAGE_SENSOR_ADC_CONFIG, offsetof(voltageSensorADCConfig_t, vbatscale) },
|
{ "vbat_scale", VAR_UINT8 | MASTER_VALUE, .config.minmax = { VBAT_SCALE_MIN, VBAT_SCALE_MAX }, PG_VOLTAGE_SENSOR_ADC_CONFIG, offsetof(voltageSensorADCConfig_t, vbatscale) },
|
||||||
|
|
|
@ -105,6 +105,9 @@ PG_RESET_TEMPLATE(batteryConfig_t, batteryConfig,
|
||||||
.batteryCapacity = 0,
|
.batteryCapacity = 0,
|
||||||
.currentMeterSource = DEFAULT_CURRENT_METER_SOURCE,
|
.currentMeterSource = DEFAULT_CURRENT_METER_SOURCE,
|
||||||
|
|
||||||
|
// cells
|
||||||
|
.setBatteryCellCount = 0, //0 will be ignored
|
||||||
|
|
||||||
// warnings / alerts
|
// warnings / alerts
|
||||||
.useVBatAlerts = true,
|
.useVBatAlerts = true,
|
||||||
.useConsumptionAlerts = false,
|
.useConsumptionAlerts = false,
|
||||||
|
@ -187,7 +190,14 @@ void batteryUpdatePresence(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
consumptionState = voltageState = BATTERY_OK;
|
consumptionState = voltageState = BATTERY_OK;
|
||||||
batteryCellCount = cells;
|
if (batteryConfig()->setBatteryCellCount != 0)
|
||||||
|
{
|
||||||
|
batteryCellCount = batteryConfig()->setBatteryCellCount;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
batteryCellCount = cells;
|
||||||
|
}
|
||||||
batteryWarningVoltage = batteryCellCount * batteryConfig()->vbatwarningcellvoltage;
|
batteryWarningVoltage = batteryCellCount * batteryConfig()->vbatwarningcellvoltage;
|
||||||
batteryCriticalVoltage = batteryCellCount * batteryConfig()->vbatmincellvoltage;
|
batteryCriticalVoltage = batteryCellCount * batteryConfig()->vbatmincellvoltage;
|
||||||
lowVoltageCutoff.percentage = 100;
|
lowVoltageCutoff.percentage = 100;
|
||||||
|
|
|
@ -40,6 +40,9 @@ typedef struct batteryConfig_s {
|
||||||
currentMeterSource_e currentMeterSource; // source of battery current meter used, either ADC, Virtual or ESC
|
currentMeterSource_e currentMeterSource; // source of battery current meter used, either ADC, Virtual or ESC
|
||||||
uint16_t batteryCapacity; // mAh
|
uint16_t batteryCapacity; // mAh
|
||||||
|
|
||||||
|
// cells
|
||||||
|
uint8_t setBatteryCellCount; // number of cells in battery, used for overwriting auto-detected cell count if someone has issues with it.
|
||||||
|
|
||||||
// warnings / alerts
|
// warnings / alerts
|
||||||
bool useVBatAlerts; // Issue alerts based on VBat readings
|
bool useVBatAlerts; // Issue alerts based on VBat readings
|
||||||
bool useConsumptionAlerts; // Issue alerts based on total power consumption
|
bool useConsumptionAlerts; // Issue alerts based on total power consumption
|
||||||
|
|
|
@ -100,6 +100,7 @@ void targetConfiguration(void)
|
||||||
batteryConfigMutable()->batteryCapacity = 250;
|
batteryConfigMutable()->batteryCapacity = 250;
|
||||||
batteryConfigMutable()->vbatmincellvoltage = 28;
|
batteryConfigMutable()->vbatmincellvoltage = 28;
|
||||||
batteryConfigMutable()->vbatwarningcellvoltage = 33;
|
batteryConfigMutable()->vbatwarningcellvoltage = 33;
|
||||||
|
batteryConfigMutable()->setBatteryCellCount = 0;
|
||||||
|
|
||||||
*customMotorMixerMutable(0) = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
|
*customMotorMixerMutable(0) = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
|
||||||
*customMotorMixerMutable(1) = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
|
*customMotorMixerMutable(1) = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
|
||||||
|
|
|
@ -381,6 +381,7 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
|
||||||
bstWrite8(batteryConfig()->vbatmincellvoltage);
|
bstWrite8(batteryConfig()->vbatmincellvoltage);
|
||||||
bstWrite8(batteryConfig()->vbatmaxcellvoltage);
|
bstWrite8(batteryConfig()->vbatmaxcellvoltage);
|
||||||
bstWrite8(batteryConfig()->vbatwarningcellvoltage);
|
bstWrite8(batteryConfig()->vbatwarningcellvoltage);
|
||||||
|
bstWrite8(batteryConfig()->setBatteryCellCount);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case BST_FEATURE:
|
case BST_FEATURE:
|
||||||
|
@ -538,6 +539,7 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
|
||||||
batteryConfigMutable()->vbatmincellvoltage = bstRead8(); // vbatlevel_warn1 in MWC2.3 GUI
|
batteryConfigMutable()->vbatmincellvoltage = bstRead8(); // vbatlevel_warn1 in MWC2.3 GUI
|
||||||
batteryConfigMutable()->vbatmaxcellvoltage = bstRead8(); // vbatlevel_warn2 in MWC2.3 GUI
|
batteryConfigMutable()->vbatmaxcellvoltage = bstRead8(); // vbatlevel_warn2 in MWC2.3 GUI
|
||||||
batteryConfigMutable()->vbatwarningcellvoltage = bstRead8(); // vbatlevel when buzzer starts to alert
|
batteryConfigMutable()->vbatwarningcellvoltage = bstRead8(); // vbatlevel when buzzer starts to alert
|
||||||
|
batteryConfigMutable()->setBatteryCellCount = bstRead8();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case BST_ACC_CALIBRATION:
|
case BST_ACC_CALIBRATION:
|
||||||
|
|
|
@ -58,6 +58,7 @@ void targetConfiguration(void)
|
||||||
batteryConfigMutable()->vbatmaxcellvoltage = 44;
|
batteryConfigMutable()->vbatmaxcellvoltage = 44;
|
||||||
batteryConfigMutable()->vbatmincellvoltage = 32;
|
batteryConfigMutable()->vbatmincellvoltage = 32;
|
||||||
batteryConfigMutable()->vbatwarningcellvoltage = 33;
|
batteryConfigMutable()->vbatwarningcellvoltage = 33;
|
||||||
|
batteryConfigMutable()->setBatteryCellCount = 0;
|
||||||
|
|
||||||
rxConfigMutable()->spektrum_sat_bind = 5;
|
rxConfigMutable()->spektrum_sat_bind = 5;
|
||||||
rxConfigMutable()->spektrum_sat_bind_autoreset = 1;
|
rxConfigMutable()->spektrum_sat_bind_autoreset = 1;
|
||||||
|
|
|
@ -52,6 +52,7 @@ TEST(BatteryTest, BatteryADCToVoltage)
|
||||||
.currentMeterType = CURRENT_SENSOR_NONE,
|
.currentMeterType = CURRENT_SENSOR_NONE,
|
||||||
.multiwiiCurrentMeterOutput = 0,
|
.multiwiiCurrentMeterOutput = 0,
|
||||||
.batteryCapacity = 2200,
|
.batteryCapacity = 2200,
|
||||||
|
.setBatteryCellCount = 0,
|
||||||
};
|
};
|
||||||
|
|
||||||
batteryInit(&batteryConfig);
|
batteryInit(&batteryConfig);
|
||||||
|
@ -112,6 +113,7 @@ TEST(BatteryTest, BatteryState)
|
||||||
.currentMeterType = CURRENT_SENSOR_NONE,
|
.currentMeterType = CURRENT_SENSOR_NONE,
|
||||||
.multiwiiCurrentMeterOutput = 0,
|
.multiwiiCurrentMeterOutput = 0,
|
||||||
.batteryCapacity = 2200,
|
.batteryCapacity = 2200,
|
||||||
|
.setBatteryCellCount = 0,
|
||||||
};
|
};
|
||||||
|
|
||||||
batteryInit(&batteryConfig);
|
batteryInit(&batteryConfig);
|
||||||
|
@ -171,6 +173,7 @@ TEST(BatteryTest, CellCount)
|
||||||
.currentMeterType = CURRENT_SENSOR_NONE,
|
.currentMeterType = CURRENT_SENSOR_NONE,
|
||||||
.multiwiiCurrentMeterOutput = 0,
|
.multiwiiCurrentMeterOutput = 0,
|
||||||
.batteryCapacity = 2200,
|
.batteryCapacity = 2200,
|
||||||
|
.setBatteryCellCount = 0,
|
||||||
};
|
};
|
||||||
|
|
||||||
batteryInit(&batteryConfig);
|
batteryInit(&batteryConfig);
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue