Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Increase battery voltage resolution to 10mV #2668

4 changes: 2 additions & 2 deletions src/main/blackbox/blackbox.c
Original file line number Diff line number Diff line change
Expand Up @@ -1362,12 +1362,12 @@ static bool blackboxWriteSysinfo(void)

BLACKBOX_PRINT_HEADER_LINE_CUSTOM(
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) {
blackboxPrintfHeaderLine("vbat_scale", "%u", batteryConfig()->vbatscale);
blackboxPrintfHeaderLine("vbat_scale", "%lu", batteryConfig()->vbatscale);
} else {
xmitState.headerIndex += 2; // Skip the next two vbat fields too
}
);
BLACKBOX_PRINT_HEADER_LINE("vbatcellvoltage", "%u,%u,%u", batteryConfig()->vbatmincellvoltage,
BLACKBOX_PRINT_HEADER_LINE("vbatcellvoltage", "%lu,%lu,%lu", batteryConfig()->vbatmincellvoltage,
batteryConfig()->vbatwarningcellvoltage,
batteryConfig()->vbatmaxcellvoltage);
BLACKBOX_PRINT_HEADER_LINE("vbatref", "%u", vbatReference);
Expand Down
2 changes: 1 addition & 1 deletion src/main/fc/cli.c
Original file line number Diff line number Diff line change
Expand Up @@ -2328,7 +2328,7 @@ static void cliStatus(char *cmdline)
rtcGetDateTime(&dt);
dateTimeFormatLocal(buf, &dt);
cliPrintLinef("Current Time: %s", buf);
cliPrintLinef("Voltage: %d * 0.1V (%dS battery - %s)", vbat, batteryCellCount, getBatteryStateString());
cliPrintLinef("Voltage: %lu * 0.01V (%dS battery - %s)", vbat, batteryCellCount, getBatteryStateString());
cliPrintf("CPU Clock=%dMHz", (SystemCoreClock / 1000000));

#if (FLASH_SIZE > 64)
Expand Down
124 changes: 107 additions & 17 deletions src/main/fc/fc_msp.c
Original file line number Diff line number Diff line change
Expand Up @@ -399,6 +399,53 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
}
break;

case MSP2_ANALOG:
sbufWriteU16(dst, vbat);
sbufWriteU16(dst, (uint16_t)constrain(mAhDrawn, 0, 0xFFFF)); // milliamp hours drawn from battery
sbufWriteU16(dst, rssi);
if (batteryConfig()->multiwiiCurrentMeterOutput) {
sbufWriteU16(dst, (uint16_t)constrain(amperage * 10, 0, 0xFFFF)); // send amperage in 0.001 A steps. Negative range is truncated to zero
} else
sbufWriteU16(dst, (int16_t)constrain(amperage, -0x8000, 0x7FFF)); // send amperage in 0.01 A steps, range is -320A to 320A
break;

case MSP2_MISC:
sbufWriteU16(dst, rxConfig()->midrc);

sbufWriteU16(dst, motorConfig()->minthrottle);
sbufWriteU16(dst, motorConfig()->maxthrottle);
sbufWriteU16(dst, motorConfig()->mincommand);

sbufWriteU16(dst, failsafeConfig()->failsafe_throttle);

#ifdef USE_GPS
sbufWriteU8(dst, gpsConfig()->provider); // gps_type
sbufWriteU8(dst, 0); // TODO gps_baudrate (an index, cleanflight uses a uint32_t
sbufWriteU8(dst, gpsConfig()->sbasMode); // gps_ubx_sbas
#else
sbufWriteU8(dst, 0); // gps_type
sbufWriteU8(dst, 0); // TODO gps_baudrate (an index, cleanflight uses a uint32_t
sbufWriteU8(dst, 0); // gps_ubx_sbas
#endif
sbufWriteU8(dst, batteryConfig()->multiwiiCurrentMeterOutput);
sbufWriteU8(dst, rxConfig()->rssi_channel);
sbufWriteU8(dst, 0);

sbufWriteU16(dst, compassConfig()->mag_declination / 10);

sbufWriteU16(dst, batteryConfig()->vbatscale);
sbufWriteU16(dst, batteryConfig()->vbatmincellvoltage);
sbufWriteU16(dst, batteryConfig()->vbatmaxcellvoltage);
sbufWriteU16(dst, batteryConfig()->vbatwarningcellvoltage);
break;

case MSP2_VOLTAGE_METER_CONFIG:
sbufWriteU16(dst, batteryConfig()->vbatscale);
sbufWriteU16(dst, batteryConfig()->vbatmincellvoltage);
sbufWriteU16(dst, batteryConfig()->vbatmaxcellvoltage);
sbufWriteU16(dst, batteryConfig()->vbatwarningcellvoltage);
break;

case MSP_RAW_IMU:
{
// Hack scale due to choice of units for sensor data in multiwii
Expand Down Expand Up @@ -502,7 +549,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
break;

case MSP_ANALOG:
sbufWriteU8(dst, (uint8_t)constrain(vbat, 0, 255));
sbufWriteU8(dst, (uint8_t)constrain(vbat / 10, 0, 255));
sbufWriteU16(dst, (uint16_t)constrain(mAhDrawn, 0, 0xFFFF)); // milliamp hours drawn from battery
sbufWriteU16(dst, rssi);
if (batteryConfig()->multiwiiCurrentMeterOutput) {
Expand Down Expand Up @@ -608,10 +655,10 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF

sbufWriteU16(dst, compassConfig()->mag_declination / 10);

sbufWriteU8(dst, batteryConfig()->vbatscale);
sbufWriteU8(dst, batteryConfig()->vbatmincellvoltage);
sbufWriteU8(dst, batteryConfig()->vbatmaxcellvoltage);
sbufWriteU8(dst, batteryConfig()->vbatwarningcellvoltage);
sbufWriteU8(dst, batteryConfig()->vbatscale / 10);
sbufWriteU8(dst, batteryConfig()->vbatmincellvoltage / 10);
sbufWriteU8(dst, batteryConfig()->vbatmaxcellvoltage / 10);
sbufWriteU8(dst, batteryConfig()->vbatwarningcellvoltage / 10);
break;

case MSP_MOTOR_PINS:
Expand Down Expand Up @@ -697,10 +744,10 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
break;

case MSP_VOLTAGE_METER_CONFIG:
sbufWriteU8(dst, batteryConfig()->vbatscale);
sbufWriteU8(dst, batteryConfig()->vbatmincellvoltage);
sbufWriteU8(dst, batteryConfig()->vbatmaxcellvoltage);
sbufWriteU8(dst, batteryConfig()->vbatwarningcellvoltage);
sbufWriteU8(dst, batteryConfig()->vbatscale / 10);
sbufWriteU8(dst, batteryConfig()->vbatmincellvoltage / 10);
sbufWriteU8(dst, batteryConfig()->vbatmaxcellvoltage / 10);
sbufWriteU8(dst, batteryConfig()->vbatwarningcellvoltage / 10);
break;

case MSP_CURRENT_METER_CONFIG:
Expand Down Expand Up @@ -1394,10 +1441,46 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
sbufReadU16(src);
#endif

batteryConfigMutable()->vbatscale = sbufReadU8(src); // actual vbatscale as intended
batteryConfigMutable()->vbatmincellvoltage = sbufReadU8(src); // vbatlevel_warn1 in MWC2.3 GUI
batteryConfigMutable()->vbatmaxcellvoltage = sbufReadU8(src); // vbatlevel_warn2 in MWC2.3 GUI
batteryConfigMutable()->vbatwarningcellvoltage = sbufReadU8(src); // vbatlevel when buzzer starts to alert
batteryConfigMutable()->vbatscale = sbufReadU8(src) * 10; // actual vbatscale as intended
batteryConfigMutable()->vbatmincellvoltage = sbufReadU8(src) * 10; // vbatlevel_warn1 in MWC2.3 GUI
batteryConfigMutable()->vbatmaxcellvoltage = sbufReadU8(src) * 10; // vbatlevel_warn2 in MWC2.3 GUI
batteryConfigMutable()->vbatwarningcellvoltage = sbufReadU8(src) * 10; // vbatlevel when buzzer starts to alert
break;

case MSP2_SET_MISC:
tmp = sbufReadU16(src);
if (tmp < 1600 && tmp > 1400)
rxConfigMutable()->midrc = tmp;

motorConfigMutable()->minthrottle = sbufReadU16(src);
motorConfigMutable()->maxthrottle = sbufReadU16(src);
motorConfigMutable()->mincommand = sbufReadU16(src);

failsafeConfigMutable()->failsafe_throttle = sbufReadU16(src);

#ifdef USE_GPS
gpsConfigMutable()->provider = sbufReadU8(src); // gps_type
sbufReadU8(src); // gps_baudrate
gpsConfigMutable()->sbasMode = sbufReadU8(src); // gps_ubx_sbas
#else
sbufReadU8(src); // gps_type
sbufReadU8(src); // gps_baudrate
sbufReadU8(src); // gps_ubx_sbas
#endif
batteryConfigMutable()->multiwiiCurrentMeterOutput = sbufReadU8(src);
rxConfigMutable()->rssi_channel = sbufReadU8(src);
sbufReadU8(src);

#ifdef USE_MAG
compassConfigMutable()->mag_declination = sbufReadU16(src) * 10;
#else
sbufReadU16(src);
#endif

batteryConfigMutable()->vbatscale = sbufReadU16(src); // actual vbatscale as intended
batteryConfigMutable()->vbatmincellvoltage = sbufReadU16(src); // vbatlevel_warn1 in MWC2.3 GUI
batteryConfigMutable()->vbatmaxcellvoltage = sbufReadU16(src); // vbatlevel_warn2 in MWC2.3 GUI
batteryConfigMutable()->vbatwarningcellvoltage = sbufReadU16(src); // vbatlevel when buzzer starts to alert
break;

case MSP_SET_MOTOR:
Expand Down Expand Up @@ -1839,10 +1922,17 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
break;

case MSP_SET_VOLTAGE_METER_CONFIG:
batteryConfigMutable()->vbatscale = sbufReadU8(src); // actual vbatscale as intended
batteryConfigMutable()->vbatmincellvoltage = sbufReadU8(src); // vbatlevel_warn1 in MWC2.3 GUI
batteryConfigMutable()->vbatmaxcellvoltage = sbufReadU8(src); // vbatlevel_warn2 in MWC2.3 GUI
batteryConfigMutable()->vbatwarningcellvoltage = sbufReadU8(src); // vbatlevel when buzzer starts to alert
batteryConfigMutable()->vbatscale = sbufReadU8(src) * 10; // actual vbatscale as intended
batteryConfigMutable()->vbatmincellvoltage = sbufReadU8(src) * 10; // vbatlevel_warn1 in MWC2.3 GUI
batteryConfigMutable()->vbatmaxcellvoltage = sbufReadU8(src) * 10; // vbatlevel_warn2 in MWC2.3 GUI
batteryConfigMutable()->vbatwarningcellvoltage = sbufReadU8(src) * 10; // vbatlevel when buzzer starts to alert
break;

case MSP2_SET_VOLTAGE_METER_CONFIG:
batteryConfigMutable()->vbatscale = sbufReadU16(src); // actual vbatscale as intended
batteryConfigMutable()->vbatmincellvoltage = sbufReadU16(src); // vbatlevel_warn1 in MWC2.3 GUI
batteryConfigMutable()->vbatmaxcellvoltage = sbufReadU16(src); // vbatlevel_warn2 in MWC2.3 GUI
batteryConfigMutable()->vbatwarningcellvoltage = sbufReadU16(src); // vbatlevel when buzzer starts to alert
break;

case MSP_SET_CURRENT_METER_CONFIG:
Expand Down
16 changes: 10 additions & 6 deletions src/main/fc/settings.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -473,18 +473,18 @@ groups:
- name: vbat_max_cell_voltage
field: vbatmaxcellvoltage
condition: USE_ADC
min: 10
max: 50
min: 100
max: 500
- name: vbat_min_cell_voltage
field: vbatmincellvoltage
condition: USE_ADC
min: 10
max: 50
min: 100
max: 500
- name: vbat_warning_cell_voltage
field: vbatwarningcellvoltage
condition: USE_ADC
min: 10
max: 50
min: 100
max: 500
- name: current_meter_scale
field: currentMeterScale
min: -10000
Expand Down Expand Up @@ -1361,6 +1361,10 @@ groups:
field: item_pos[OSD_MAIN_BATT_VOLTAGE]
min: 0
max: OSD_POS_MAX_CLI
- name: osd_main_voltage_decimals
field: main_voltage_decimals
min: 1
max: 2
- name: osd_rssi_pos
field: item_pos[OSD_RSSI_VALUE]
min: 0
Expand Down
2 changes: 1 addition & 1 deletion src/main/io/dashboard.c
Original file line number Diff line number Diff line change
Expand Up @@ -357,7 +357,7 @@ static void showStatusPage(void)

if (feature(FEATURE_VBAT)) {
i2c_OLED_set_line(rowIndex++);
tfp_sprintf(lineBuffer, "V: %d.%1d ", vbat / 10, vbat % 10);
tfp_sprintf(lineBuffer, "V: %d.%1d ", vbat / 100, vbat % 100);
padLineBufferToChar(12);
i2c_OLED_send_string(lineBuffer);

Expand Down
21 changes: 11 additions & 10 deletions src/main/io/osd.c
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ static timeUs_t flyTime = 0;

typedef struct statistic_s {
uint16_t max_speed;
int16_t min_voltage; // /10
uint16_t min_voltage; // /100
int16_t max_current; // /10
int16_t min_rssi;
int32_t max_altitude;
Expand Down Expand Up @@ -821,9 +821,9 @@ static bool osdDrawSingleElement(uint8_t item)

case OSD_MAIN_BATT_VOLTAGE:
osdFormatBatteryChargeSymbol(buff);
osdFormatCentiNumber(buff + 1, vbat * 10, 0, 1, 0, 3);
buff[4] = 'V';
buff[5] = '\0';
osdFormatCentiNumber(buff + 1, vbat, 0, osdConfig()->main_voltage_decimals, 0, osdConfig()->main_voltage_decimals + 2);
buff[osdConfig()->main_voltage_decimals + 3] = 'V';
buff[osdConfig()->main_voltage_decimals + 4] = '\0';
osdUpdateBatteryTextAttributes(&elemAttr);
break;

Expand Down Expand Up @@ -1248,7 +1248,7 @@ static bool osdDrawSingleElement(uint8_t item)
case OSD_POWER:
{
// TODO: SYM_WATTS?
tfp_sprintf(buff, "W%-3d", amperage * vbat / 1000);
tfp_sprintf(buff, "W%-3d", amperage * vbat / 10000);
break;
}

Expand Down Expand Up @@ -1360,9 +1360,9 @@ static bool osdDrawSingleElement(uint8_t item)
// cells might yield more significant digits
uint16_t cellBattCentiVolts = vbat * 10 / batteryCellCount;
osdFormatBatteryChargeSymbol(buff);
osdFormatCentiNumber(buff + 1, cellBattCentiVolts, 0, 2, 0, 3);
buff[4] = 'V';
buff[5] = '\0';
osdFormatCentiNumber(buff + 1, cellBattCentiVolts, 0, osdConfig()->main_voltage_decimals, 0, 3);
buff[osdConfig()->main_voltage_decimals + 2] = 'V';
buff[osdConfig()->main_voltage_decimals + 3] = '\0';
osdUpdateBatteryTextAttributes(&elemAttr);
break;
}
Expand Down Expand Up @@ -1571,6 +1571,7 @@ void pgResetFn_osdConfig(osdConfig_t *osdConfig)
osdConfig->sidebar_scroll_arrows = 0;

osdConfig->units = OSD_UNIT_METRIC;
osdConfig->main_voltage_decimals = 1;
}

void osdInit(displayPort_t *osdDisplayPortToUse)
Expand Down Expand Up @@ -1608,7 +1609,7 @@ static void osdResetStats(void)
{
stats.max_current = 0;
stats.max_speed = 0;
stats.min_voltage = 500;
stats.min_voltage = 5000;
stats.max_current = 0;
stats.min_rssi = 99;
stats.max_altitude = 0;
Expand Down Expand Up @@ -1667,7 +1668,7 @@ static void osdShowStats(void)
}

displayWrite(osdDisplayPort, statNameX, top, "MIN BATTERY :");
tfp_sprintf(buff, "%d.%1dV", stats.min_voltage / 10, stats.min_voltage % 10);
tfp_sprintf(buff, "%d.%1dV", stats.min_voltage / 100, stats.min_voltage % 100);
displayWrite(osdDisplayPort, statValuesX, top++, buff);

displayWrite(osdDisplayPort, statNameX, top, "MIN RSSI :");
Expand Down
1 change: 1 addition & 0 deletions src/main/io/osd.h
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,7 @@ typedef struct osdConfig_s {
uint8_t row_shiftdown;

// Preferences
uint8_t main_voltage_decimals;
uint8_t ahi_reverse_roll;
osd_crosshairs_style_e crosshairs_style;
osd_sidebar_scroll_e left_sidebar_scroll;
Expand Down
9 changes: 7 additions & 2 deletions src/main/msp/msp_protocol_v2_inav.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,5 +18,10 @@
// iNav specific IDs start from 0x2000
// See https://github.com/iNavFlight/inav/wiki/MSP-V2#msp-v2-message-catalogue

#define MSP2_INAV_STATUS 0x2000
#define MSP2_INAV_OPTICAL_FLOW 0x2001
#define MSP2_INAV_STATUS 0x2000
#define MSP2_INAV_OPTICAL_FLOW 0x2001
#define MSP2_ANALOG 0x2002
#define MSP2_MISC 0x2003
#define MSP2_SET_MISC 0x2004
#define MSP2_VOLTAGE_METER_CONFIG 0x2005
#define MSP2_SET_VOLTAGE_METER_CONFIG 0x2006
2 changes: 1 addition & 1 deletion src/main/rx/eleres.c
Original file line number Diff line number Diff line change
Expand Up @@ -294,7 +294,7 @@ static void telemetryRX(void)
rfTxBuffer[0] = 0x54;
rfTxBuffer[1] = localRssi;
rfTxBuffer[2] = quality;
rfTxBuffer[3] = vbat;
rfTxBuffer[3] = vbat / 10;
rfTxBuffer[4] = themp;
rfTxBuffer[5] = curr & 0xff;
rfTxBuffer[6] = pres>>8;
Expand Down
2 changes: 1 addition & 1 deletion src/main/rx/jetiexbus.c
Original file line number Diff line number Diff line change
Expand Up @@ -521,7 +521,7 @@ void handleJetiExBusTelemetry(void)
}

if ((jetiExBusRequestFrame[EXBUS_HEADER_DATA_ID] == EXBUS_EX_REQUEST) && (calcCRC16(jetiExBusRequestFrame, jetiExBusRequestFrame[EXBUS_HEADER_MSG_LEN]) == 0)) {
jetiExSensors[EX_VOLTAGE].value = vbat;
jetiExSensors[EX_VOLTAGE].value = vbat / 10;
jetiExSensors[EX_CURRENT].value = amperage;
jetiExSensors[EX_ALTITUDE].value = baro.BaroAlt;
jetiExSensors[EX_CAPACITY].value = mAhDrawn;
Expand Down
8 changes: 4 additions & 4 deletions src/main/sensors/battery.c
Original file line number Diff line number Diff line change
Expand Up @@ -65,9 +65,9 @@ PG_RESET_TEMPLATE(batteryConfig_t, batteryConfig,
.vbatscale = VBAT_SCALE_DEFAULT,
.vbatresdivval = VBAT_RESDIVVAL_DEFAULT,
.vbatresdivmultiplier = VBAT_RESDIVMULTIPLIER_DEFAULT,
.vbatmaxcellvoltage = 43,
.vbatmincellvoltage = 33,
.vbatwarningcellvoltage = 35,
.vbatmaxcellvoltage = 430,
.vbatmincellvoltage = 330,
.vbatwarningcellvoltage = 350,
.currentMeterOffset = 0,
.currentMeterScale = CURRENT_METER_SCALE,
.batteryCapacity = 0,
Expand All @@ -94,7 +94,7 @@ static void updateBatteryVoltage(uint32_t vbatTimeDelta)

#define VBATTERY_STABLE_DELAY 40
/* Batt Hysteresis of +/-100mV */
#define VBATT_HYSTERESIS 1
#define VBATT_HYSTERESIS 10

void batteryUpdate(uint32_t vbatTimeDelta)
{
Expand Down
12 changes: 6 additions & 6 deletions src/main/sensors/battery.h
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,12 @@
#include "config/parameter_group.h"

#ifndef VBAT_SCALE_DEFAULT
#define VBAT_SCALE_DEFAULT 110
#define VBAT_SCALE_DEFAULT 1100
#endif
#define VBAT_RESDIVVAL_DEFAULT 10
#define VBAT_RESDIVMULTIPLIER_DEFAULT 1
#define VBAT_SCALE_MIN 0
#define VBAT_SCALE_MAX 255
#define VBAT_SCALE_MAX 65535

#ifndef CURRENT_METER_SCALE
#define CURRENT_METER_SCALE 400 // for Allegro ACS758LCB-100U (40mV/A)
Expand All @@ -39,12 +39,12 @@ typedef enum {
} currentSensor_e;

typedef struct batteryConfig_s {
uint8_t vbatscale; // adjust this to match battery voltage to reported value
uint16_t vbatscale; // adjust this to match battery voltage to reported value
uint8_t vbatresdivval; // resistor divider R2 (default NAZE 10(K))
uint8_t vbatresdivmultiplier; // multiplier for scale (e.g. 2.5:1 ratio with multiplier of 4 can use '100' instead of '25' in ratio) to get better precision
uint8_t vbatmaxcellvoltage; // maximum voltage per cell, used for auto-detecting battery voltage in 0.1V units, default is 43 (4.3V)
uint8_t vbatmincellvoltage; // minimum voltage per cell, this triggers battery critical alarm, in 0.1V units, default is 33 (3.3V)
uint8_t vbatwarningcellvoltage; // warning voltage per cell, this triggers battery warning alarm, in 0.1V units, default is 35 (3.5V)
uint16_t vbatmaxcellvoltage; // maximum voltage per cell, used for auto-detecting battery voltage in 0.01V units, default is 430 (4.3V)
uint16_t vbatmincellvoltage; // minimum voltage per cell, this triggers battery critical alarm, in 0.01V units, default is 330 (3.3V)
uint16_t vbatwarningcellvoltage; // warning voltage per cell, this triggers battery warning alarm, in 0.01V units, default is 350 (3.5V)

int16_t currentMeterScale; // scale the current sensor output voltage to milliamps. Value in 1/10th mV/A
int16_t currentMeterOffset; // offset of the current sensor in millivolt steps
Expand Down
Loading