mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-25 17:25:18 +03:00
Improve battery monitoring (#2705)
* increase battery voltage resolution to 10mV * increase battery voltage resolution to 10mV: update VBATT_HYSTERESIS * increase battery voltage resolution to 10mV: fix telemetry and other places where vbat calculations needs to be divided by 10 * increase battery voltage resolution to 10mV: revert blackbox data to 100mV resolution because modifying the viewer is not trivial * increase battery voltage resolution to 10mV: change new MSPv2 frame type names to follow convention * smartport telemetry: remove wrong and now irrelevant comments * Improve battery monitoring * improve battery monitoring: fix/simplify the batteryAdcToVoltage function * improve battery monitoring: Add OSD voltage decimals setting to OSD MISC menu * improve battery monitoring: clean the batteryConfig struct * improve battery monitoring: increase batteryConfig PG group version to 1 * improve battery monitoring: change capacity settings type from uin16_t to uint32_t (65Wh is not very large, it is about 6Ah for a 3S Li-Po) * improve battery monitoring: rename capacity settings * improve battery monitoring: improve OSD code * improve battery monitoring: simplified taskUpdateBattery * improve battery monitoring: use unfiltered vbat to decide if the battery is full
This commit is contained in:
parent
d0feb4d998
commit
f00194c167
35 changed files with 646 additions and 311 deletions
|
@ -511,13 +511,21 @@ 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) {
|
||||
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
|
||||
sbufWriteU16(dst, (int16_t)constrain(amperage, -0x8000, 0x7FFF)); // send amperage in 0.01 A steps, range is -320A to 320A
|
||||
break;
|
||||
|
||||
case MSP2_INAV_ANALOG:
|
||||
sbufWriteU16(dst, vbat);
|
||||
sbufWriteU8(dst, batteryCellCount);
|
||||
sbufWriteU8(dst, calculateBatteryPercentage());
|
||||
sbufWriteU16(dst, constrain(power, 0, 0x7FFFFFFF)); // power draw
|
||||
sbufWriteU16(dst, (uint16_t)constrain(mAhDrawn, 0, 0xFFFF)); // milliamp hours drawn from battery
|
||||
sbufWriteU16(dst, (uint16_t)constrain(mWhDrawn, 0, 0xFFFF)); // milliWatt hours drawn from battery
|
||||
sbufWriteU16(dst, rssi);
|
||||
sbufWriteU16(dst, (int16_t)constrain(amperage, -0x8000, 0x7FFF)); // send amperage in 0.01 A steps, range is -320A to 320A
|
||||
break;
|
||||
|
||||
case MSP_ARMING_CONFIG:
|
||||
|
@ -633,16 +641,65 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
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, 0); // multiwiiCurrentMeterOutput
|
||||
sbufWriteU8(dst, rxConfig()->rssi_channel);
|
||||
sbufWriteU8(dst, 0);
|
||||
|
||||
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()->voltage.scale / 10);
|
||||
sbufWriteU8(dst, batteryConfig()->voltage.cellMin / 10);
|
||||
sbufWriteU8(dst, batteryConfig()->voltage.cellMax / 10);
|
||||
sbufWriteU8(dst, batteryConfig()->voltage.cellWarning / 10);
|
||||
break;
|
||||
|
||||
case MSP2_INAV_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, rxConfig()->rssi_channel);
|
||||
sbufWriteU8(dst, 0);
|
||||
|
||||
sbufWriteU16(dst, compassConfig()->mag_declination / 10);
|
||||
|
||||
sbufWriteU16(dst, batteryConfig()->voltage.scale);
|
||||
sbufWriteU16(dst, batteryConfig()->voltage.cellMin);
|
||||
sbufWriteU16(dst, batteryConfig()->voltage.cellMax);
|
||||
sbufWriteU16(dst, batteryConfig()->voltage.cellWarning);
|
||||
|
||||
sbufWriteU32(dst, batteryConfig()->capacity.value);
|
||||
sbufWriteU32(dst, batteryConfig()->capacity.warning);
|
||||
sbufWriteU32(dst, batteryConfig()->capacity.critical);
|
||||
sbufWriteU8(dst, batteryConfig()->capacity.unit);
|
||||
break;
|
||||
|
||||
case MSP2_INAV_BATTERY_CONFIG:
|
||||
sbufWriteU16(dst, batteryConfig()->voltage.scale);
|
||||
sbufWriteU16(dst, batteryConfig()->voltage.cellMin);
|
||||
sbufWriteU16(dst, batteryConfig()->voltage.cellMax);
|
||||
sbufWriteU16(dst, batteryConfig()->voltage.cellWarning);
|
||||
|
||||
sbufWriteU16(dst, batteryConfig()->current.offset);
|
||||
sbufWriteU16(dst, batteryConfig()->current.scale);
|
||||
|
||||
sbufWriteU32(dst, batteryConfig()->capacity.value);
|
||||
sbufWriteU32(dst, batteryConfig()->capacity.warning);
|
||||
sbufWriteU32(dst, batteryConfig()->capacity.critical);
|
||||
sbufWriteU8(dst, batteryConfig()->capacity.unit);
|
||||
break;
|
||||
|
||||
case MSP_MOTOR_PINS:
|
||||
|
@ -728,17 +785,17 @@ 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()->voltage.scale / 10);
|
||||
sbufWriteU8(dst, batteryConfig()->voltage.cellMin / 10);
|
||||
sbufWriteU8(dst, batteryConfig()->voltage.cellMax / 10);
|
||||
sbufWriteU8(dst, batteryConfig()->voltage.cellWarning / 10);
|
||||
break;
|
||||
|
||||
case MSP_CURRENT_METER_CONFIG:
|
||||
sbufWriteU16(dst, batteryConfig()->currentMeterScale);
|
||||
sbufWriteU16(dst, batteryConfig()->currentMeterOffset);
|
||||
sbufWriteU8(dst, batteryConfig()->currentMeterType);
|
||||
sbufWriteU16(dst, batteryConfig()->batteryCapacity);
|
||||
sbufWriteU16(dst, batteryConfig()->current.scale);
|
||||
sbufWriteU16(dst, batteryConfig()->current.offset);
|
||||
sbufWriteU8(dst, batteryConfig()->current.type);
|
||||
sbufWriteU16(dst, constrain(batteryConfig()->capacity.value, 0, 0xFFFF));
|
||||
break;
|
||||
|
||||
case MSP_MIXER:
|
||||
|
@ -798,8 +855,8 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
sbufWriteU16(dst, boardAlignment()->pitchDeciDegrees);
|
||||
sbufWriteU16(dst, boardAlignment()->yawDeciDegrees);
|
||||
|
||||
sbufWriteU16(dst, batteryConfig()->currentMeterScale);
|
||||
sbufWriteU16(dst, batteryConfig()->currentMeterOffset);
|
||||
sbufWriteU16(dst, batteryConfig()->current.scale);
|
||||
sbufWriteU16(dst, batteryConfig()->current.offset);
|
||||
break;
|
||||
|
||||
case MSP_CF_SERIAL_CONFIG:
|
||||
|
@ -883,7 +940,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
#endif
|
||||
sbufWriteU8(dst, osdConfig()->units);
|
||||
sbufWriteU8(dst, osdConfig()->rssi_alarm);
|
||||
sbufWriteU16(dst, osdConfig()->cap_alarm);
|
||||
sbufWriteU16(dst, batteryConfig()->capacity.warning);
|
||||
sbufWriteU16(dst, osdConfig()->time_alarm);
|
||||
sbufWriteU16(dst, osdConfig()->alt_alarm);
|
||||
sbufWriteU16(dst, osdConfig()->dist_alarm);
|
||||
|
@ -1454,7 +1511,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
sbufReadU8(src); // gps_baudrate
|
||||
sbufReadU8(src); // gps_ubx_sbas
|
||||
#endif
|
||||
batteryConfigMutable()->multiwiiCurrentMeterOutput = sbufReadU8(src);
|
||||
sbufReadU8(src); // multiwiiCurrentMeterOutput
|
||||
rxConfigMutable()->rssi_channel = sbufReadU8(src);
|
||||
sbufReadU8(src);
|
||||
|
||||
|
@ -1464,10 +1521,74 @@ 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()->voltage.scale = sbufReadU8(src) * 10;
|
||||
batteryConfigMutable()->voltage.cellMin = sbufReadU8(src) * 10; // vbatlevel_warn1 in MWC2.3 GUI
|
||||
batteryConfigMutable()->voltage.cellMax = sbufReadU8(src) * 10; // vbatlevel_warn2 in MWC2.3 GUI
|
||||
batteryConfigMutable()->voltage.cellWarning = sbufReadU8(src) * 10; // vbatlevel when buzzer starts to alert
|
||||
break;
|
||||
|
||||
case MSP2_INAV_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
|
||||
sbufReadU8(src); // multiwiiCurrentMeterOutput
|
||||
rxConfigMutable()->rssi_channel = sbufReadU8(src);
|
||||
sbufReadU8(src);
|
||||
|
||||
#ifdef USE_MAG
|
||||
compassConfigMutable()->mag_declination = sbufReadU16(src) * 10;
|
||||
#else
|
||||
sbufReadU16(src);
|
||||
#endif
|
||||
|
||||
batteryConfigMutable()->voltage.scale = sbufReadU16(src);
|
||||
batteryConfigMutable()->voltage.cellMin = sbufReadU16(src);
|
||||
batteryConfigMutable()->voltage.cellMax = sbufReadU16(src);
|
||||
batteryConfigMutable()->voltage.cellWarning = sbufReadU16(src);
|
||||
|
||||
batteryConfigMutable()->capacity.value = sbufReadU32(src);
|
||||
batteryConfigMutable()->capacity.warning = sbufReadU32(src);
|
||||
batteryConfigMutable()->capacity.critical = sbufReadU32(src);
|
||||
batteryConfigMutable()->capacity.unit = sbufReadU8(src);
|
||||
if ((batteryConfig()->capacity.unit != BAT_CAPACITY_UNIT_MAH) && (batteryConfig()->capacity.unit != BAT_CAPACITY_UNIT_MWH)) {
|
||||
batteryConfigMutable()->capacity.unit = BAT_CAPACITY_UNIT_MAH;
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
break;
|
||||
|
||||
case MSP2_INAV_SET_BATTERY_CONFIG:
|
||||
batteryConfigMutable()->voltage.scale = sbufReadU16(src);
|
||||
batteryConfigMutable()->voltage.cellMin = sbufReadU16(src);
|
||||
batteryConfigMutable()->voltage.cellMax = sbufReadU16(src);
|
||||
batteryConfigMutable()->voltage.cellWarning = sbufReadU16(src);
|
||||
|
||||
batteryConfigMutable()->current.offset = sbufReadU16(src);
|
||||
batteryConfigMutable()->current.scale = sbufReadU16(src);
|
||||
|
||||
batteryConfigMutable()->capacity.value = sbufReadU32(src);
|
||||
batteryConfigMutable()->capacity.warning = sbufReadU32(src);
|
||||
batteryConfigMutable()->capacity.critical = sbufReadU32(src);
|
||||
batteryConfigMutable()->capacity.unit = sbufReadU8(src);
|
||||
if ((batteryConfig()->capacity.unit != BAT_CAPACITY_UNIT_MAH) && (batteryConfig()->capacity.unit != BAT_CAPACITY_UNIT_MWH)) {
|
||||
batteryConfigMutable()->capacity.unit = BAT_CAPACITY_UNIT_MAH;
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
break;
|
||||
|
||||
case MSP_SET_MOTOR:
|
||||
|
@ -1788,7 +1909,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
#endif
|
||||
osdConfigMutable()->units = sbufReadU8(src);
|
||||
osdConfigMutable()->rssi_alarm = sbufReadU8(src);
|
||||
osdConfigMutable()->cap_alarm = sbufReadU16(src);
|
||||
batteryConfigMutable()->capacity.warning = sbufReadU16(src);
|
||||
osdConfigMutable()->time_alarm = sbufReadU16(src);
|
||||
osdConfigMutable()->alt_alarm = sbufReadU16(src);
|
||||
// Won't be read if they weren't provided
|
||||
|
@ -1921,17 +2042,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()->voltage.scale = sbufReadU8(src) * 10;
|
||||
batteryConfigMutable()->voltage.cellMin = sbufReadU8(src) * 10;
|
||||
batteryConfigMutable()->voltage.cellMax = sbufReadU8(src) * 10;
|
||||
batteryConfigMutable()->voltage.cellWarning = sbufReadU8(src) * 10;
|
||||
break;
|
||||
|
||||
case MSP_SET_CURRENT_METER_CONFIG:
|
||||
batteryConfigMutable()->currentMeterScale = sbufReadU16(src);
|
||||
batteryConfigMutable()->currentMeterOffset = sbufReadU16(src);
|
||||
batteryConfigMutable()->currentMeterType = sbufReadU8(src);
|
||||
batteryConfigMutable()->batteryCapacity = sbufReadU16(src);
|
||||
batteryConfigMutable()->current.scale = sbufReadU16(src);
|
||||
batteryConfigMutable()->current.offset = sbufReadU16(src);
|
||||
batteryConfigMutable()->current.type = sbufReadU8(src);
|
||||
batteryConfigMutable()->capacity.value = sbufReadU16(src);
|
||||
break;
|
||||
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
|
@ -2002,8 +2123,8 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
boardAlignmentMutable()->pitchDeciDegrees = sbufReadU16(src); // board_align_pitch
|
||||
boardAlignmentMutable()->yawDeciDegrees = sbufReadU16(src); // board_align_yaw
|
||||
|
||||
batteryConfigMutable()->currentMeterScale = sbufReadU16(src);
|
||||
batteryConfigMutable()->currentMeterOffset = sbufReadU16(src);
|
||||
batteryConfigMutable()->current.scale = sbufReadU16(src);
|
||||
batteryConfigMutable()->current.offset = sbufReadU16(src);
|
||||
break;
|
||||
|
||||
case MSP_SET_CF_SERIAL_CONFIG:
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue