1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-21 15:25:36 +03:00

CF/BF - delete legacy multiwiiCurrentMeterOutput setting.

This commit is contained in:
Hydra 2017-03-16 19:17:43 +00:00 committed by Dominic Clifton
parent 067d3c0ac2
commit c6d1148134
4 changed files with 8 additions and 21 deletions

View file

@ -626,7 +626,6 @@ static const clivalue_t valueTable[] = {
{ "vbat_min_cell_voltage", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 10, 50 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbatmincellvoltage) }, { "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_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) }, { "vbat_hysteresis", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 250 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbathysteresis) },
{ "mwii_ibat_output", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, multiwiiCurrentMeterOutput) },
{ "current_meter", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_CURRENT_METER }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, currentMeterSource) }, { "current_meter", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_CURRENT_METER }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, currentMeterSource) },
{ "battery_meter", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_VOLTAGE_METER }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, voltageMeterSource) }, { "battery_meter", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_VOLTAGE_METER }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, voltageMeterSource) },
{ "bat_detect_thresh", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 200 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, batteryNotPresentLevel) }, { "bat_detect_thresh", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 200 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, batteryNotPresentLevel) },

View file

@ -731,11 +731,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
sbufWriteU8(dst, (uint8_t)constrain(getBatteryVoltage(), 0, 255)); sbufWriteU8(dst, (uint8_t)constrain(getBatteryVoltage(), 0, 255));
sbufWriteU16(dst, (uint16_t)constrain(getMAhDrawn(), 0, 0xFFFF)); // milliamp hours drawn from battery sbufWriteU16(dst, (uint16_t)constrain(getMAhDrawn(), 0, 0xFFFF)); // milliamp hours drawn from battery
sbufWriteU16(dst, rssi); sbufWriteU16(dst, rssi);
sbufWriteU16(dst, (int16_t)constrain(getAmperage(), -0x8000, 0x7FFF)); // send current in 0.01 A steps, range is -320A to 320A
if(batteryConfig()->multiwiiCurrentMeterOutput) {
sbufWriteU16(dst, (uint16_t)constrain(getAmperage() * 10, 0, 0xFFFF)); // send current in 0.001 A steps. Negative range is truncated to zero
} else
sbufWriteU16(dst, (int16_t)constrain(getAmperage(), -0x8000, 0x7FFF)); // send current in 0.01 A steps, range is -320A to 320A
break; break;
} }
@ -835,13 +831,13 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
sbufWriteU8(dst, 0); // TODO gps_baudrate (an index, cleanflight uses a uint32_t sbufWriteU8(dst, 0); // TODO gps_baudrate (an index, cleanflight uses a uint32_t
sbufWriteU8(dst, 0); // gps_ubx_sbas sbufWriteU8(dst, 0); // gps_ubx_sbas
#endif #endif
sbufWriteU8(dst, batteryConfig()->multiwiiCurrentMeterOutput); sbufWriteU8(dst, 0); // was multiwiiCurrentMeterOutput
sbufWriteU8(dst, rxConfig()->rssi_channel); sbufWriteU8(dst, rxConfig()->rssi_channel);
sbufWriteU8(dst, 0); sbufWriteU8(dst, 0);
sbufWriteU16(dst, compassConfig()->mag_declination / 10); sbufWriteU16(dst, compassConfig()->mag_declination / 10);
sbufWriteU8(dst, 0); // batteryConfig()->vbatscale sbufWriteU8(dst, 0); // was vbatscale
sbufWriteU8(dst, batteryConfig()->vbatmincellvoltage); sbufWriteU8(dst, batteryConfig()->vbatmincellvoltage);
sbufWriteU8(dst, batteryConfig()->vbatmaxcellvoltage); sbufWriteU8(dst, batteryConfig()->vbatmaxcellvoltage);
sbufWriteU8(dst, batteryConfig()->vbatwarningcellvoltage); sbufWriteU8(dst, batteryConfig()->vbatwarningcellvoltage);
@ -1435,13 +1431,13 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
sbufReadU8(src); // gps_baudrate sbufReadU8(src); // gps_baudrate
sbufReadU8(src); // gps_ubx_sbas sbufReadU8(src); // gps_ubx_sbas
#endif #endif
batteryConfigMutable()->multiwiiCurrentMeterOutput = sbufReadU8(src); sbufReadU8(src); // legacy - was multiwiiCurrentMeterOutput
rxConfigMutable()->rssi_channel = sbufReadU8(src); rxConfigMutable()->rssi_channel = sbufReadU8(src);
sbufReadU8(src); sbufReadU8(src);
compassConfigMutable()->mag_declination = sbufReadU16(src) * 10; compassConfigMutable()->mag_declination = sbufReadU16(src) * 10;
sbufReadU8(src); // actual vbatscale as intended // was batteryConfigMutable()->vbatscale sbufReadU8(src); // legacy - was vbatscale
batteryConfigMutable()->vbatmincellvoltage = sbufReadU8(src); // vbatlevel_warn1 in MWC2.3 GUI batteryConfigMutable()->vbatmincellvoltage = sbufReadU8(src); // vbatlevel_warn1 in MWC2.3 GUI
batteryConfigMutable()->vbatmaxcellvoltage = sbufReadU8(src); // vbatlevel_warn2 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()->vbatwarningcellvoltage = sbufReadU8(src); // vbatlevel when buzzer starts to alert

View file

@ -46,10 +46,6 @@ typedef struct batteryConfig_s {
bool useConsumptionAlerts; // Issue alerts based on total power consumption bool useConsumptionAlerts; // Issue alerts based on total power consumption
uint8_t consumptionWarningPercentage; // Percentage of remaining capacity that should trigger a battery warning 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 vbathysteresis; // hysteresis for alarm, default 1 = 0.1V
// FIXME this doesn't belong in here since it's a concern of MSP, not of the battery code.
uint8_t multiwiiCurrentMeterOutput; // if set to 1 output the amperage in milliamp steps instead of 0.01A steps via msp
} batteryConfig_t; } batteryConfig_t;
PG_DECLARE(batteryConfig_t, batteryConfig); PG_DECLARE(batteryConfig_t, batteryConfig);

View file

@ -680,11 +680,7 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
bstWrite8((uint8_t)constrain(getBatteryVoltage(), 0, 255)); bstWrite8((uint8_t)constrain(getBatteryVoltage(), 0, 255));
bstWrite16((uint16_t)constrain(getMAhDrawn(), 0, 0xFFFF)); // milliamp hours drawn from battery bstWrite16((uint16_t)constrain(getMAhDrawn(), 0, 0xFFFF)); // milliamp hours drawn from battery
bstWrite16(rssi); bstWrite16(rssi);
// FIXME - what does the TBS OSD actually need? the 'multiwiiCurrentMeterOutput' setting pre-dates the TBS i2c_bst code so likely we can just output exactly what we need. bstWrite16((int16_t)constrain(getAmperage(), -0x8000, 0x7FFF)); // send amperage in 0.01 A steps, range is -320A to 320A
if(batteryConfig()->multiwiiCurrentMeterOutput) {
bstWrite16((uint16_t)constrain(getAmperage() * 10, 0, 0xFFFF)); // send amperage in 0.001 A steps. Negative range is truncated to zero
} else
bstWrite16((int16_t)constrain(getAmperage(), -0x8000, 0x7FFF)); // send amperage in 0.01 A steps, range is -320A to 320A
break; break;
case BST_ARMING_CONFIG: case BST_ARMING_CONFIG:
bstWrite8(armingConfig()->auto_disarm_delay); bstWrite8(armingConfig()->auto_disarm_delay);
@ -771,7 +767,7 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
bstWrite8(0); // TODO gps_baudrate (an index, cleanflight uses a uint32_t bstWrite8(0); // TODO gps_baudrate (an index, cleanflight uses a uint32_t
bstWrite8(0); // gps_ubx_sbas bstWrite8(0); // gps_ubx_sbas
#endif #endif
bstWrite8(batteryConfig()->multiwiiCurrentMeterOutput); bstWrite8(0); // legacy - was multiwiiCurrentMeterOutput);
bstWrite8(rxConfig()->rssi_channel); bstWrite8(rxConfig()->rssi_channel);
bstWrite8(0); bstWrite8(0);
@ -1154,7 +1150,7 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
bstRead8(); // gps_baudrate bstRead8(); // gps_baudrate
bstRead8(); // gps_ubx_sbas bstRead8(); // gps_ubx_sbas
#endif #endif
batteryConfigMutable()->multiwiiCurrentMeterOutput = bstRead8(); bstRead8(); // legacy - was multiwiiCurrentMeterOutput
rxConfigMutable()->rssi_channel = bstRead8(); rxConfigMutable()->rssi_channel = bstRead8();
bstRead8(); bstRead8();