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

Get setting default values from settings.yaml (#6595)

* Get setting default values from settings.yaml

* settings: Make the generator more robust and versatile

- Add support for resolving types and values in multiple compilers
- Add support for resolving types and values in clang 10
- Add support for using the host compiler for resolving the settings

This allows us to run the generator for the unit tests, since they now
need the settings_generated.h file to get the default setting values
from it.

* Fix regexps in settings.rb and add execution bit

* Fix git revision issue

* Fix issue with settings validation

* Fix issue with targets not defining USE_MAG

Co-authored-by: Alberto García Hierro <alberto@garciahierro.com>
This commit is contained in:
Michel Pastor 2021-04-07 17:48:09 +02:00 committed by GitHub
parent 7b705bccac
commit fc0e5e2741
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
85 changed files with 1708 additions and 1875 deletions

View file

@ -487,7 +487,11 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
sbufWriteU16(dst, gyroRateDps(i));
}
for (int i = 0; i < 3; i++) {
#ifdef USE_MAG
sbufWriteU16(dst, mag.magADC[i]);
#else
sbufWriteU16(dst, 0);
#endif
}
}
break;
@ -785,12 +789,23 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
sbufWriteU8(dst, rxConfig()->rssi_channel);
sbufWriteU8(dst, 0);
#ifdef USE_MAG
sbufWriteU16(dst, compassConfig()->mag_declination / 10);
#else
sbufWriteU16(dst, 0);
#endif
#ifdef USE_ADC
sbufWriteU8(dst, batteryMetersConfig()->voltage.scale / 10);
sbufWriteU8(dst, currentBatteryProfile->voltage.cellMin / 10);
sbufWriteU8(dst, currentBatteryProfile->voltage.cellMax / 10);
sbufWriteU8(dst, currentBatteryProfile->voltage.cellWarning / 10);
#else
sbufWriteU8(dst, 0);
sbufWriteU8(dst, 0);
sbufWriteU8(dst, 0);
sbufWriteU8(dst, 0);
#endif
break;
case MSP2_INAV_MISC:
@ -813,8 +828,13 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
#endif
sbufWriteU8(dst, rxConfig()->rssi_channel);
#ifdef USE_MAG
sbufWriteU16(dst, compassConfig()->mag_declination / 10);
#else
sbufWriteU16(dst, 0);
#endif
#ifdef USE_ADC
sbufWriteU16(dst, batteryMetersConfig()->voltage.scale);
sbufWriteU8(dst, batteryMetersConfig()->voltageSource);
sbufWriteU8(dst, currentBatteryProfile->cells);
@ -822,6 +842,15 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
sbufWriteU16(dst, currentBatteryProfile->voltage.cellMin);
sbufWriteU16(dst, currentBatteryProfile->voltage.cellMax);
sbufWriteU16(dst, currentBatteryProfile->voltage.cellWarning);
#else
sbufWriteU16(dst, 0);
sbufWriteU8(dst, 0);
sbufWriteU8(dst, 0);
sbufWriteU16(dst, 0);
sbufWriteU16(dst, 0);
sbufWriteU16(dst, 0);
sbufWriteU16(dst, 0);
#endif
sbufWriteU32(dst, currentBatteryProfile->capacity.value);
sbufWriteU32(dst, currentBatteryProfile->capacity.warning);
@ -841,6 +870,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
break;
case MSP2_INAV_BATTERY_CONFIG:
#ifdef USE_ADC
sbufWriteU16(dst, batteryMetersConfig()->voltage.scale);
sbufWriteU8(dst, batteryMetersConfig()->voltageSource);
sbufWriteU8(dst, currentBatteryProfile->cells);
@ -848,6 +878,15 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
sbufWriteU16(dst, currentBatteryProfile->voltage.cellMin);
sbufWriteU16(dst, currentBatteryProfile->voltage.cellMax);
sbufWriteU16(dst, currentBatteryProfile->voltage.cellWarning);
#else
sbufWriteU16(dst, 0);
sbufWriteU8(dst, 0);
sbufWriteU8(dst, 0);
sbufWriteU16(dst, 0);
sbufWriteU16(dst, 0);
sbufWriteU16(dst, 0);
sbufWriteU16(dst, 0);
#endif
sbufWriteU16(dst, batteryMetersConfig()->current.offset);
sbufWriteU16(dst, batteryMetersConfig()->current.scale);
@ -947,10 +986,17 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
break;
case MSP_VOLTAGE_METER_CONFIG:
#ifdef USE_ADC
sbufWriteU8(dst, batteryMetersConfig()->voltage.scale / 10);
sbufWriteU8(dst, currentBatteryProfile->voltage.cellMin / 10);
sbufWriteU8(dst, currentBatteryProfile->voltage.cellMax / 10);
sbufWriteU8(dst, currentBatteryProfile->voltage.cellWarning / 10);
#else
sbufWriteU8(dst, 0);
sbufWriteU8(dst, 0);
sbufWriteU8(dst, 0);
sbufWriteU8(dst, 0);
#endif
break;
case MSP_CURRENT_METER_CONFIG:
@ -969,15 +1015,25 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
sbufWriteU16(dst, rxConfig()->maxcheck);
sbufWriteU16(dst, PWM_RANGE_MIDDLE);
sbufWriteU16(dst, rxConfig()->mincheck);
#ifdef USE_SPEKTRUM_BIND
sbufWriteU8(dst, rxConfig()->spektrum_sat_bind);
#else
sbufWriteU8(dst, 0);
#endif
sbufWriteU16(dst, rxConfig()->rx_min_usec);
sbufWriteU16(dst, rxConfig()->rx_max_usec);
sbufWriteU8(dst, 0); // for compatibility with betaflight (rcInterpolation)
sbufWriteU8(dst, 0); // for compatibility with betaflight (rcInterpolationInterval)
sbufWriteU16(dst, 0); // for compatibility with betaflight (airModeActivateThreshold)
#ifdef USE_RX_SPI
sbufWriteU8(dst, rxConfig()->rx_spi_protocol);
sbufWriteU32(dst, rxConfig()->rx_spi_id);
sbufWriteU8(dst, rxConfig()->rx_spi_rf_channel_count);
#else
sbufWriteU8(dst, 0);
sbufWriteU32(dst, 0);
sbufWriteU8(dst, 0);
#endif
sbufWriteU8(dst, 0); // for compatibility with betaflight (fpvCamAngleDegrees)
sbufWriteU8(dst, rxConfig()->receiverType);
break;
@ -1154,7 +1210,11 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
case MSP_SENSOR_ALIGNMENT:
sbufWriteU8(dst, gyroConfig()->gyro_align);
sbufWriteU8(dst, accelerometerConfig()->acc_align);
#ifdef USE_MAG
sbufWriteU8(dst, compassConfig()->mag_align);
#else
sbufWriteU8(dst, 0);
#endif
#ifdef USE_OPFLOW
sbufWriteU8(dst, opticalFlowConfig()->opflow_align);
#else
@ -1831,10 +1891,17 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
sbufReadU16(src);
#endif
#ifdef USE_ADC
batteryMetersConfigMutable()->voltage.scale = sbufReadU8(src) * 10;
currentBatteryProfileMutable->voltage.cellMin = sbufReadU8(src) * 10; // vbatlevel_warn1 in MWC2.3 GUI
currentBatteryProfileMutable->voltage.cellMax = sbufReadU8(src) * 10; // vbatlevel_warn2 in MWC2.3 GUI
currentBatteryProfileMutable->voltage.cellWarning = sbufReadU8(src) * 10; // vbatlevel when buzzer starts to alert
#else
sbufReadU8(src);
sbufReadU8(src);
sbufReadU8(src);
sbufReadU8(src);
#endif
} else
return MSP_RESULT_ERROR;
break;
@ -1869,6 +1936,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
sbufReadU16(src);
#endif
#ifdef USE_ADC
batteryMetersConfigMutable()->voltage.scale = sbufReadU16(src);
batteryMetersConfigMutable()->voltageSource = sbufReadU8(src);
currentBatteryProfileMutable->cells = sbufReadU8(src);
@ -1876,6 +1944,15 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
currentBatteryProfileMutable->voltage.cellMin = sbufReadU16(src);
currentBatteryProfileMutable->voltage.cellMax = sbufReadU16(src);
currentBatteryProfileMutable->voltage.cellWarning = sbufReadU16(src);
#else
sbufReadU16(src);
sbufReadU8(src);
sbufReadU8(src);
sbufReadU16(src);
sbufReadU16(src);
sbufReadU16(src);
sbufReadU16(src);
#endif
currentBatteryProfileMutable->capacity.value = sbufReadU32(src);
currentBatteryProfileMutable->capacity.warning = sbufReadU32(src);
@ -1895,6 +1972,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
case MSP2_INAV_SET_BATTERY_CONFIG:
if (dataSize == 29) {
#ifdef USE_ADC
batteryMetersConfigMutable()->voltage.scale = sbufReadU16(src);
batteryMetersConfigMutable()->voltageSource = sbufReadU8(src);
currentBatteryProfileMutable->cells = sbufReadU8(src);
@ -1902,6 +1980,15 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
currentBatteryProfileMutable->voltage.cellMin = sbufReadU16(src);
currentBatteryProfileMutable->voltage.cellMax = sbufReadU16(src);
currentBatteryProfileMutable->voltage.cellWarning = sbufReadU16(src);
#else
sbufReadU16(src);
sbufReadU8(src);
sbufReadU8(src);
sbufReadU16(src);
sbufReadU16(src);
sbufReadU16(src);
sbufReadU16(src);
#endif
batteryMetersConfigMutable()->current.offset = sbufReadU16(src);
batteryMetersConfigMutable()->current.scale = sbufReadU16(src);
@ -2538,10 +2625,17 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
case MSP_SET_VOLTAGE_METER_CONFIG:
if (dataSize >= 4) {
#ifdef USE_ADC
batteryMetersConfigMutable()->voltage.scale = sbufReadU8(src) * 10;
currentBatteryProfileMutable->voltage.cellMin = sbufReadU8(src) * 10;
currentBatteryProfileMutable->voltage.cellMax = sbufReadU8(src) * 10;
currentBatteryProfileMutable->voltage.cellWarning = sbufReadU8(src) * 10;
#else
sbufReadU8(src);
sbufReadU8(src);
sbufReadU8(src);
sbufReadU8(src);
#endif
} else
return MSP_RESULT_ERROR;
break;
@ -2570,15 +2664,25 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
rxConfigMutable()->maxcheck = sbufReadU16(src);
sbufReadU16(src); // midrc
rxConfigMutable()->mincheck = sbufReadU16(src);
#ifdef USE_SPEKTRUM_BIND
rxConfigMutable()->spektrum_sat_bind = sbufReadU8(src);
#else
sbufReadU8(src);
#endif
rxConfigMutable()->rx_min_usec = sbufReadU16(src);
rxConfigMutable()->rx_max_usec = sbufReadU16(src);
sbufReadU8(src); // for compatibility with betaflight (rcInterpolation)
sbufReadU8(src); // for compatibility with betaflight (rcInterpolationInterval)
sbufReadU16(src); // for compatibility with betaflight (airModeActivateThreshold)
#ifdef USE_RX_SPI
rxConfigMutable()->rx_spi_protocol = sbufReadU8(src);
rxConfigMutable()->rx_spi_id = sbufReadU32(src);
rxConfigMutable()->rx_spi_rf_channel_count = sbufReadU8(src);
#else
sbufReadU8(src);
sbufReadU32(src);
sbufReadU8(src);
#endif
sbufReadU8(src); // for compatibility with betaflight (fpvCamAngleDegrees)
rxConfigMutable()->receiverType = sbufReadU8(src); // Won't be modified if buffer is not large enough
} else