Refactor sat count checks and GPS trust code
[betaflight.git] / src / main / config / config.c
blob3eb171e2e77d47e84d740d2bb8ffba66b4a6c1b2
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
21 #include <stdbool.h>
22 #include <stdint.h>
23 #include <string.h>
24 #include <math.h>
26 #include "platform.h"
28 #include "blackbox/blackbox.h"
30 #include "build/debug.h"
32 #include "cli/cli.h"
34 #include "common/sensor_alignment.h"
36 #include "config/config_eeprom.h"
37 #include "config/feature.h"
39 #include "drivers/dshot_command.h"
40 #include "drivers/motor.h"
41 #include "drivers/system.h"
43 #include "fc/controlrate_profile.h"
44 #include "fc/core.h"
45 #include "fc/rc.h"
46 #include "fc/rc_adjustments.h"
47 #include "fc/rc_controls.h"
48 #include "fc/runtime_config.h"
50 #include "flight/failsafe.h"
51 #include "flight/imu.h"
52 #include "flight/mixer.h"
53 #include "flight/pid.h"
54 #include "flight/pid_init.h"
55 #include "flight/rpm_filter.h"
56 #include "flight/servos.h"
57 #include "flight/position.h"
59 #include "io/beeper.h"
60 #include "io/gps.h"
61 #include "io/ledstrip.h"
62 #include "io/serial.h"
63 #include "io/vtx.h"
65 #include "msp/msp_box.h"
67 #include "osd/osd.h"
69 #include "pg/adc.h"
70 #include "pg/beeper.h"
71 #include "pg/beeper_dev.h"
72 #include "pg/displayport_profiles.h"
73 #include "pg/gyrodev.h"
74 #include "pg/motor.h"
75 #include "pg/pg.h"
76 #include "pg/pg_ids.h"
77 #include "pg/rx.h"
78 #include "pg/rx_spi.h"
79 #include "pg/sdcard.h"
80 #include "pg/vtx_table.h"
82 #include "rx/rx.h"
83 #include "rx/rx_spi.h"
85 #include "scheduler/scheduler.h"
87 #include "sensors/acceleration.h"
88 #include "sensors/battery.h"
89 #include "sensors/compass.h"
90 #include "sensors/gyro.h"
92 #include "config.h"
94 #include "drivers/dshot.h"
96 static bool configIsDirty; /* someone indicated that the config is modified and it is not yet saved */
98 static bool rebootRequired = false; // set if a config change requires a reboot to take effect
100 static bool eepromWriteInProgress = false;
102 pidProfile_t *currentPidProfile;
104 #ifndef RX_SPI_DEFAULT_PROTOCOL
105 #define RX_SPI_DEFAULT_PROTOCOL 0
106 #endif
108 PG_REGISTER_WITH_RESET_TEMPLATE(pilotConfig_t, pilotConfig, PG_PILOT_CONFIG, 1);
110 PG_RESET_TEMPLATE(pilotConfig_t, pilotConfig,
111 .name = { 0 },
112 .displayName = { 0 },
115 PG_REGISTER_WITH_RESET_TEMPLATE(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 3);
117 PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
118 .pidProfileIndex = 0,
119 .activeRateProfile = 0,
120 .debug_mode = DEBUG_MODE,
121 .task_statistics = true,
122 .rateProfile6PosSwitch = false,
123 .cpu_overclock = DEFAULT_CPU_OVERCLOCK,
124 .powerOnArmingGraceTime = 5,
125 .boardIdentifier = TARGET_BOARD_IDENTIFIER,
126 .hseMhz = SYSTEM_HSE_VALUE, // Only used for F4 and G4 targets
127 .configurationState = CONFIGURATION_STATE_DEFAULTS_BARE,
128 .enableStickArming = false,
131 bool isEepromWriteInProgress(void)
133 return eepromWriteInProgress;
136 uint8_t getCurrentPidProfileIndex(void)
138 return systemConfig()->pidProfileIndex;
141 static void loadPidProfile(void)
143 currentPidProfile = pidProfilesMutable(systemConfig()->pidProfileIndex);
146 uint8_t getCurrentControlRateProfileIndex(void)
148 return systemConfig()->activeRateProfile;
151 uint16_t getCurrentMinthrottle(void)
153 return motorConfig()->minthrottle;
156 void resetConfig(void)
158 pgResetAll();
160 #if defined(USE_TARGET_CONFIG)
161 targetConfiguration();
162 #endif
165 static void activateConfig(void)
167 loadPidProfile();
168 loadControlRateProfile();
170 initRcProcessing();
172 activeAdjustmentRangeReset();
174 pidInit(currentPidProfile);
176 rcControlsInit();
178 failsafeReset();
179 #ifdef USE_ACC
180 setAccelerationTrims(&accelerometerConfigMutable()->accZero);
181 accInitFilters();
182 #endif
184 imuConfigure(throttleCorrectionConfig()->throttle_correction_angle, throttleCorrectionConfig()->throttle_correction_value);
186 #if defined(USE_LED_STRIP_STATUS_MODE)
187 reevaluateLedConfig();
188 #endif
190 initActiveBoxIds();
193 static void adjustFilterLimit(uint16_t *parm, uint16_t resetValue)
195 if (*parm > LPF_MAX_HZ) {
196 *parm = resetValue;
200 static void validateAndFixRatesSettings(void)
202 for (unsigned profileIndex = 0; profileIndex < CONTROL_RATE_PROFILE_COUNT; profileIndex++) {
203 const ratesType_e ratesType = controlRateProfilesMutable(profileIndex)->rates_type;
204 for (unsigned axis = FD_ROLL; axis <= FD_YAW; axis++) {
205 controlRateProfilesMutable(profileIndex)->rcRates[axis] = constrain(controlRateProfilesMutable(profileIndex)->rcRates[axis], 0, ratesSettingLimits[ratesType].rc_rate_limit);
206 controlRateProfilesMutable(profileIndex)->rates[axis] = constrain(controlRateProfilesMutable(profileIndex)->rates[axis], 0, ratesSettingLimits[ratesType].srate_limit);
207 controlRateProfilesMutable(profileIndex)->rcExpo[axis] = constrain(controlRateProfilesMutable(profileIndex)->rcExpo[axis], 0, ratesSettingLimits[ratesType].expo_limit);
212 static void validateAndFixMinSatsGpsConfig(void)
214 if (gpsConfig()->gpsMinimumSats >= gpsConfig()->gpsRequiredSats) {
215 gpsConfigMutable()->gpsRequiredSats = GPS_REQUIRED_SAT_COUNT;
216 gpsConfigMutable()->gpsMinimumSats = GPS_MINIMUM_SAT_COUNT;
220 static void validateAndFixConfig(void)
222 #if !defined(USE_QUAD_MIXER_ONLY)
223 // Reset unsupported mixer mode to default.
224 // This check will be gone when motor/servo mixers are loaded dynamically
225 // by configurator as a part of configuration procedure.
227 mixerMode_e mixerMode = mixerConfigMutable()->mixerMode;
229 if (!(mixerMode == MIXER_CUSTOM || mixerMode == MIXER_CUSTOM_AIRPLANE || mixerMode == MIXER_CUSTOM_TRI)) {
230 if (mixers[mixerMode].motorCount && mixers[mixerMode].motor == NULL)
231 mixerConfigMutable()->mixerMode = MIXER_CUSTOM;
232 #ifdef USE_SERVOS
233 if (mixers[mixerMode].useServo && servoMixers[mixerMode].servoRuleCount == 0)
234 mixerConfigMutable()->mixerMode = MIXER_CUSTOM_AIRPLANE;
235 #endif
237 #endif
239 if (!isSerialConfigValid(serialConfig())) {
240 pgResetFn_serialConfig(serialConfigMutable());
243 #if defined(USE_GPS)
244 const serialPortConfig_t *gpsSerial = findSerialPortConfig(FUNCTION_GPS);
245 if (gpsConfig()->provider == GPS_MSP && gpsSerial) {
246 serialRemovePort(gpsSerial->identifier);
248 #endif
249 if (
250 #if defined(USE_GPS)
251 gpsConfig()->provider != GPS_MSP && !gpsSerial &&
252 #endif
253 true) {
254 featureDisableImmediate(FEATURE_GPS);
257 for (unsigned i = 0; i < PID_PROFILE_COUNT; i++) {
258 // Fix filter settings to handle cases where an older configurator was used that
259 // allowed higher cutoff limits from previous firmware versions.
260 adjustFilterLimit(&pidProfilesMutable(i)->dterm_lpf1_static_hz, LPF_MAX_HZ);
261 adjustFilterLimit(&pidProfilesMutable(i)->dterm_lpf2_static_hz, LPF_MAX_HZ);
262 adjustFilterLimit(&pidProfilesMutable(i)->dterm_notch_hz, LPF_MAX_HZ);
263 adjustFilterLimit(&pidProfilesMutable(i)->dterm_notch_cutoff, 0);
265 // Prevent invalid notch cutoff
266 if (pidProfilesMutable(i)->dterm_notch_cutoff >= pidProfilesMutable(i)->dterm_notch_hz) {
267 pidProfilesMutable(i)->dterm_notch_hz = 0;
270 #ifdef USE_DYN_LPF
271 //Prevent invalid dynamic lowpass
272 if (pidProfilesMutable(i)->dterm_lpf1_dyn_min_hz > pidProfilesMutable(i)->dterm_lpf1_dyn_max_hz) {
273 pidProfilesMutable(i)->dterm_lpf1_dyn_min_hz = 0;
275 #endif
277 if (pidProfilesMutable(i)->motor_output_limit > 100 || pidProfilesMutable(i)->motor_output_limit == 0) {
278 pidProfilesMutable(i)->motor_output_limit = 100;
281 if (pidProfilesMutable(i)->auto_profile_cell_count > MAX_AUTO_DETECT_CELL_COUNT || pidProfilesMutable(i)->auto_profile_cell_count < AUTO_PROFILE_CELL_COUNT_CHANGE) {
282 pidProfilesMutable(i)->auto_profile_cell_count = AUTO_PROFILE_CELL_COUNT_STAY;
285 // If the d_min value for any axis is >= the D gain then reset d_min to 0 for consistent Configurator behavior
286 for (unsigned axis = 0; axis <= FD_YAW; axis++) {
287 if (pidProfilesMutable(i)->d_min[axis] > pidProfilesMutable(i)->pid[axis].D) {
288 pidProfilesMutable(i)->d_min[axis] = 0;
292 #if defined(USE_BATTERY_VOLTAGE_SAG_COMPENSATION)
293 if (batteryConfig()->voltageMeterSource != VOLTAGE_METER_ADC) {
294 pidProfilesMutable(i)->vbat_sag_compensation = 0;
296 #endif
299 if (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_BRUSHED) {
300 featureDisableImmediate(FEATURE_3D);
302 if (motorConfig()->mincommand < 1000) {
303 motorConfigMutable()->mincommand = 1000;
307 if ((motorConfig()->dev.motorPwmProtocol == PWM_TYPE_STANDARD) && (motorConfig()->dev.motorPwmRate > BRUSHLESS_MOTORS_PWM_RATE)) {
308 motorConfigMutable()->dev.motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE;
311 validateAndFixGyroConfig();
313 #if defined(USE_MAG)
314 buildAlignmentFromStandardAlignment(&compassConfigMutable()->mag_customAlignment, compassConfig()->mag_alignment);
315 #endif
316 buildAlignmentFromStandardAlignment(&gyroDeviceConfigMutable(0)->customAlignment, gyroDeviceConfig(0)->alignment);
317 #if defined(USE_MULTI_GYRO)
318 buildAlignmentFromStandardAlignment(&gyroDeviceConfigMutable(1)->customAlignment, gyroDeviceConfig(1)->alignment);
319 #endif
321 #ifdef USE_ACC
322 if (accelerometerConfig()->accZero.values.roll != 0 ||
323 accelerometerConfig()->accZero.values.pitch != 0 ||
324 accelerometerConfig()->accZero.values.yaw != 0) {
325 accelerometerConfigMutable()->accZero.values.calibrationCompleted = 1;
327 #endif // USE_ACC
329 if (!(featureIsConfigured(FEATURE_RX_PARALLEL_PWM) || featureIsConfigured(FEATURE_RX_PPM) || featureIsConfigured(FEATURE_RX_SERIAL) || featureIsConfigured(FEATURE_RX_MSP) || featureIsConfigured(FEATURE_RX_SPI))) {
330 featureEnableImmediate(DEFAULT_RX_FEATURE);
333 if (featureIsConfigured(FEATURE_RX_PPM)) {
334 featureDisableImmediate(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_SPI);
337 if (featureIsConfigured(FEATURE_RX_MSP)) {
338 featureDisableImmediate(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_SPI);
341 if (featureIsConfigured(FEATURE_RX_SERIAL)) {
342 featureDisableImmediate(FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
345 #ifdef USE_RX_SPI
346 if (featureIsConfigured(FEATURE_RX_SPI)) {
347 featureDisableImmediate(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_MSP);
349 #endif // USE_RX_SPI
351 if (featureIsConfigured(FEATURE_RX_PARALLEL_PWM)) {
352 featureDisableImmediate(FEATURE_RX_SERIAL | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
355 #if defined(USE_ADC)
356 if (featureIsConfigured(FEATURE_RSSI_ADC)) {
357 rxConfigMutable()->rssi_channel = 0;
358 rxConfigMutable()->rssi_src_frame_errors = false;
359 } else
360 #endif
361 if (rxConfigMutable()->rssi_channel
362 #if defined(USE_PWM) || defined(USE_PPM)
363 || featureIsConfigured(FEATURE_RX_PPM) || featureIsConfigured(FEATURE_RX_PARALLEL_PWM)
364 #endif
366 rxConfigMutable()->rssi_src_frame_errors = false;
369 if (
370 featureIsConfigured(FEATURE_3D) || !featureIsConfigured(FEATURE_GPS) || mixerModeIsFixedWing(mixerConfig()->mixerMode)
371 #if !defined(USE_GPS) || !defined(USE_GPS_RESCUE)
372 || true
373 #endif
376 #ifdef USE_GPS_RESCUE
377 if (failsafeConfig()->failsafe_procedure == FAILSAFE_PROCEDURE_GPS_RESCUE) {
378 failsafeConfigMutable()->failsafe_procedure = FAILSAFE_PROCEDURE_DROP_IT;
380 #endif
382 if (isModeActivationConditionPresent(BOXGPSRESCUE)) {
383 removeModeActivationCondition(BOXGPSRESCUE);
387 #if defined(USE_ESC_SENSOR)
388 if (!findSerialPortConfig(FUNCTION_ESC_SENSOR)) {
389 featureDisableImmediate(FEATURE_ESC_SENSOR);
391 #endif
393 for (int i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
394 const modeActivationCondition_t *mac = modeActivationConditions(i);
396 if (mac->linkedTo) {
397 if (mac->modeId == BOXARM || isModeActivationConditionLinked(mac->linkedTo)) {
398 removeModeActivationCondition(mac->modeId);
403 #if defined(USE_DSHOT_TELEMETRY) && defined(USE_DSHOT_BITBANG)
404 if (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_PROSHOT1000 && motorConfig()->dev.useDshotTelemetry &&
405 motorConfig()->dev.useDshotBitbang == DSHOT_BITBANG_ON) {
406 motorConfigMutable()->dev.useDshotBitbang = DSHOT_BITBANG_AUTO;
408 #endif
410 #ifdef USE_ADC
411 adcConfigMutable()->vbat.enabled = (batteryConfig()->voltageMeterSource == VOLTAGE_METER_ADC);
412 adcConfigMutable()->current.enabled = (batteryConfig()->currentMeterSource == CURRENT_METER_ADC);
414 // The FrSky D SPI RX sends RSSI_ADC_PIN (if configured) as A2
415 adcConfigMutable()->rssi.enabled = featureIsEnabled(FEATURE_RSSI_ADC);
416 #ifdef USE_RX_SPI
417 adcConfigMutable()->rssi.enabled |= (featureIsEnabled(FEATURE_RX_SPI) && rxSpiConfig()->rx_spi_protocol == RX_SPI_FRSKY_D);
418 #endif
419 #endif // USE_ADC
422 // clear features that are not supported.
423 // I have kept them all here in one place, some could be moved to sections of code above.
425 #ifndef USE_PPM
426 featureDisableImmediate(FEATURE_RX_PPM);
427 #endif
429 #ifndef USE_SERIAL_RX
430 featureDisableImmediate(FEATURE_RX_SERIAL);
431 #endif
433 #if !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL2)
434 featureDisableImmediate(FEATURE_SOFTSERIAL);
435 #endif
437 #ifndef USE_RANGEFINDER
438 featureDisableImmediate(FEATURE_RANGEFINDER);
439 #endif
441 #ifndef USE_TELEMETRY
442 featureDisableImmediate(FEATURE_TELEMETRY);
443 #endif
445 #ifndef USE_PWM
446 featureDisableImmediate(FEATURE_RX_PARALLEL_PWM);
447 #endif
449 #ifndef USE_RX_MSP
450 featureDisableImmediate(FEATURE_RX_MSP);
451 #endif
453 #ifndef USE_LED_STRIP
454 featureDisableImmediate(FEATURE_LED_STRIP);
455 #endif
457 #ifndef USE_DASHBOARD
458 featureDisableImmediate(FEATURE_DASHBOARD);
459 #endif
461 #ifndef USE_OSD
462 featureDisableImmediate(FEATURE_OSD);
463 #endif
465 #ifndef USE_SERVOS
466 featureDisableImmediate(FEATURE_SERVO_TILT | FEATURE_CHANNEL_FORWARDING);
467 #endif
469 #ifndef USE_TRANSPONDER
470 featureDisableImmediate(FEATURE_TRANSPONDER);
471 #endif
473 #ifndef USE_RX_SPI
474 featureDisableImmediate(FEATURE_RX_SPI);
475 #endif
477 #ifndef USE_ESC_SENSOR
478 featureDisableImmediate(FEATURE_ESC_SENSOR);
479 #endif
481 #if !defined(USE_ADC)
482 featureDisableImmediate(FEATURE_RSSI_ADC);
483 #endif
485 #if defined(USE_BEEPER)
486 #ifdef USE_TIMER
487 if (beeperDevConfig()->frequency && !timerGetConfiguredByTag(beeperDevConfig()->ioTag)) {
488 beeperDevConfigMutable()->frequency = 0;
490 #endif
492 if (beeperConfig()->beeper_off_flags & ~BEEPER_ALLOWED_MODES) {
493 beeperConfigMutable()->beeper_off_flags = 0;
496 #ifdef USE_DSHOT
497 if (beeperConfig()->dshotBeaconOffFlags & ~DSHOT_BEACON_ALLOWED_MODES) {
498 beeperConfigMutable()->dshotBeaconOffFlags = 0;
501 if (beeperConfig()->dshotBeaconTone < DSHOT_CMD_BEACON1
502 || beeperConfig()->dshotBeaconTone > DSHOT_CMD_BEACON5) {
503 beeperConfigMutable()->dshotBeaconTone = DSHOT_CMD_BEACON1;
505 #endif
506 #endif
508 bool configuredMotorProtocolDshot = false;
509 checkMotorProtocolEnabled(&motorConfig()->dev, &configuredMotorProtocolDshot);
510 #if defined(USE_DSHOT)
511 // If using DSHOT protocol disable unsynched PWM as it's meaningless
512 if (configuredMotorProtocolDshot) {
513 motorConfigMutable()->dev.useUnsyncedPwm = false;
516 #if defined(USE_DSHOT_TELEMETRY)
517 bool nChannelTimerUsed = false;
518 for (unsigned i = 0; i < getMotorCount(); i++) {
519 const ioTag_t tag = motorConfig()->dev.ioTags[i];
520 if (tag) {
521 const timerHardware_t *timer = timerGetConfiguredByTag(tag);
522 if (timer && timer->output & TIMER_OUTPUT_N_CHANNEL) {
523 nChannelTimerUsed = true;
525 break;
530 if ((!configuredMotorProtocolDshot || (motorConfig()->dev.useDshotBitbang == DSHOT_BITBANG_OFF && (motorConfig()->dev.useBurstDshot == DSHOT_DMAR_ON || nChannelTimerUsed))) && motorConfig()->dev.useDshotTelemetry) {
531 motorConfigMutable()->dev.useDshotTelemetry = false;
533 #endif // USE_DSHOT_TELEMETRY
534 #endif // USE_DSHOT
536 #if defined(USE_OSD)
537 for (int i = 0; i < OSD_TIMER_COUNT; i++) {
538 const uint16_t t = osdConfig()->timers[i];
539 if (OSD_TIMER_SRC(t) >= OSD_TIMER_SRC_COUNT ||
540 OSD_TIMER_PRECISION(t) >= OSD_TIMER_PREC_COUNT) {
541 osdConfigMutable()->timers[i] = osdTimerDefault[i];
544 #endif
546 #if defined(USE_VTX_COMMON) && defined(USE_VTX_TABLE)
547 // reset vtx band, channel, power if outside range specified by vtxtable
548 if (vtxSettingsConfig()->channel > vtxTableConfig()->channels) {
549 vtxSettingsConfigMutable()->channel = 0;
550 if (vtxSettingsConfig()->band > 0) {
551 vtxSettingsConfigMutable()->freq = 0; // band/channel determined frequency can't be valid anymore
554 if (vtxSettingsConfig()->band > vtxTableConfig()->bands) {
555 vtxSettingsConfigMutable()->band = 0;
556 vtxSettingsConfigMutable()->freq = 0; // band/channel determined frequency can't be valid anymore
558 if (vtxSettingsConfig()->power > vtxTableConfig()->powerLevels) {
559 vtxSettingsConfigMutable()->power = 0;
561 #endif
563 validateAndFixRatesSettings(); // constrain the various rates settings to limits imposed by the rates type
565 #if defined(USE_RX_MSP_OVERRIDE)
566 if (!rxConfig()->msp_override_channels_mask) {
567 removeModeActivationCondition(BOXMSPOVERRIDE);
570 for (int i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
571 const modeActivationCondition_t *mac = modeActivationConditions(i);
572 if (mac->modeId == BOXMSPOVERRIDE && ((1 << (mac->auxChannelIndex) & (rxConfig()->msp_override_channels_mask)))) {
573 rxConfigMutable()->msp_override_channels_mask &= ~(1 << (mac->auxChannelIndex + NON_AUX_CHANNEL_COUNT));
576 #endif
578 validateAndfixMotorOutputReordering(motorConfigMutable()->dev.motorOutputReordering, MAX_SUPPORTED_MOTORS);
580 // validate that the minimum battery cell voltage is less than the maximum cell voltage
581 // reset to defaults if not
582 if (batteryConfig()->vbatmincellvoltage >= batteryConfig()->vbatmaxcellvoltage) {
583 batteryConfigMutable()->vbatmincellvoltage = VBAT_CELL_VOLTAGE_DEFAULT_MIN;
584 batteryConfigMutable()->vbatmaxcellvoltage = VBAT_CELL_VOLTAGE_DEFAULT_MAX;
587 #ifdef USE_MSP_DISPLAYPORT
588 // validate that displayport_msp_serial is referencing a valid UART that actually has MSP enabled
589 if (displayPortProfileMsp()->displayPortSerial != SERIAL_PORT_NONE) {
590 const serialPortConfig_t *portConfig = serialFindPortConfiguration(displayPortProfileMsp()->displayPortSerial);
591 if (!portConfig || !(portConfig->functionMask & FUNCTION_MSP)
592 #ifndef USE_MSP_PUSH_OVER_VCP
593 || (portConfig->identifier == SERIAL_PORT_USB_VCP)
594 #endif
596 displayPortProfileMspMutable()->displayPortSerial = SERIAL_PORT_NONE;
599 #endif
601 #if defined(TARGET_VALIDATECONFIG)
602 // This should be done at the end of the validation
603 targetValidateConfiguration();
604 #endif
606 validateAndFixMinSatsGpsConfig();
609 void validateAndFixGyroConfig(void)
611 // Fix gyro filter settings to handle cases where an older configurator was used that
612 // allowed higher cutoff limits from previous firmware versions.
613 adjustFilterLimit(&gyroConfigMutable()->gyro_lpf1_static_hz, LPF_MAX_HZ);
614 adjustFilterLimit(&gyroConfigMutable()->gyro_lpf2_static_hz, LPF_MAX_HZ);
615 adjustFilterLimit(&gyroConfigMutable()->gyro_soft_notch_hz_1, LPF_MAX_HZ);
616 adjustFilterLimit(&gyroConfigMutable()->gyro_soft_notch_cutoff_1, 0);
617 adjustFilterLimit(&gyroConfigMutable()->gyro_soft_notch_hz_2, LPF_MAX_HZ);
618 adjustFilterLimit(&gyroConfigMutable()->gyro_soft_notch_cutoff_2, 0);
620 // Prevent invalid notch cutoff
621 if (gyroConfig()->gyro_soft_notch_cutoff_1 >= gyroConfig()->gyro_soft_notch_hz_1) {
622 gyroConfigMutable()->gyro_soft_notch_hz_1 = 0;
624 if (gyroConfig()->gyro_soft_notch_cutoff_2 >= gyroConfig()->gyro_soft_notch_hz_2) {
625 gyroConfigMutable()->gyro_soft_notch_hz_2 = 0;
627 #ifdef USE_DYN_LPF
628 //Prevent invalid dynamic lowpass filter
629 if (gyroConfig()->gyro_lpf1_dyn_min_hz > gyroConfig()->gyro_lpf1_dyn_max_hz) {
630 gyroConfigMutable()->gyro_lpf1_dyn_min_hz = 0;
632 #endif
634 if (gyro.sampleRateHz > 0) {
635 float samplingTime = 1.0f / gyro.sampleRateHz;
637 // check for looptime restrictions based on motor protocol. Motor times have safety margin
638 float motorUpdateRestriction;
640 #if defined(STM32F411xE)
641 /* If bidirectional DSHOT is being used on an F411 then force DSHOT300. The motor update restrictions then applied
642 * will automatically consider the loop time and adjust pid_process_denom appropriately
644 if (motorConfig()->dev.useDshotTelemetry && (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_DSHOT600)) {
645 motorConfigMutable()->dev.motorPwmProtocol = PWM_TYPE_DSHOT300;
647 #endif
649 switch (motorConfig()->dev.motorPwmProtocol) {
650 case PWM_TYPE_STANDARD:
651 motorUpdateRestriction = 1.0f / BRUSHLESS_MOTORS_PWM_RATE;
652 break;
653 case PWM_TYPE_ONESHOT125:
654 motorUpdateRestriction = 0.0005f;
655 break;
656 case PWM_TYPE_ONESHOT42:
657 motorUpdateRestriction = 0.0001f;
658 break;
659 #ifdef USE_DSHOT
660 case PWM_TYPE_DSHOT150:
661 motorUpdateRestriction = 0.000250f;
662 break;
663 case PWM_TYPE_DSHOT300:
664 motorUpdateRestriction = 0.0001f;
665 break;
666 #endif
667 default:
668 motorUpdateRestriction = 0.00003125f;
669 break;
672 if (motorConfig()->dev.useUnsyncedPwm) {
673 bool configuredMotorProtocolDshot = false;
674 checkMotorProtocolEnabled(&motorConfig()->dev, &configuredMotorProtocolDshot);
675 // Prevent overriding the max rate of motors
676 if (!configuredMotorProtocolDshot && motorConfig()->dev.motorPwmProtocol != PWM_TYPE_STANDARD) {
677 const uint32_t maxEscRate = lrintf(1.0f / motorUpdateRestriction);
678 motorConfigMutable()->dev.motorPwmRate = MIN(motorConfig()->dev.motorPwmRate, maxEscRate);
680 } else {
681 const float pidLooptime = samplingTime * pidConfig()->pid_process_denom;
682 if (motorConfig()->dev.useDshotTelemetry) {
683 motorUpdateRestriction *= 2;
685 if (pidLooptime < motorUpdateRestriction) {
686 uint8_t minPidProcessDenom = motorUpdateRestriction / samplingTime;
687 if (motorUpdateRestriction / samplingTime > minPidProcessDenom) {
688 // if any fractional part then round up
689 minPidProcessDenom++;
691 minPidProcessDenom = constrain(minPidProcessDenom, 1, MAX_PID_PROCESS_DENOM);
692 pidConfigMutable()->pid_process_denom = MAX(pidConfigMutable()->pid_process_denom, minPidProcessDenom);
697 #ifdef USE_BLACKBOX
698 #ifndef USE_FLASHFS
699 if (blackboxConfig()->device == BLACKBOX_DEVICE_FLASH) {
700 blackboxConfigMutable()->device = BLACKBOX_DEVICE_NONE;
702 #endif // USE_FLASHFS
704 if (blackboxConfig()->device == BLACKBOX_DEVICE_SDCARD) {
705 #if defined(USE_SDCARD)
706 if (!sdcardConfig()->mode)
707 #endif
709 blackboxConfigMutable()->device = BLACKBOX_DEVICE_NONE;
712 #endif // USE_BLACKBOX
714 if (systemConfig()->activeRateProfile >= CONTROL_RATE_PROFILE_COUNT) {
715 systemConfigMutable()->activeRateProfile = 0;
717 loadControlRateProfile();
719 if (systemConfig()->pidProfileIndex >= PID_PROFILE_COUNT) {
720 systemConfigMutable()->pidProfileIndex = 0;
722 loadPidProfile();
725 bool readEEPROM(void)
727 suspendRxSignal();
729 // Sanity check, read flash
730 bool success = loadEEPROM();
732 featureInit();
734 validateAndFixConfig();
736 activateConfig();
738 resumeRxSignal();
740 return success;
743 void writeUnmodifiedConfigToEEPROM(void)
745 validateAndFixConfig();
747 suspendRxSignal();
748 eepromWriteInProgress = true;
749 writeConfigToEEPROM();
750 eepromWriteInProgress = false;
751 resumeRxSignal();
752 configIsDirty = false;
755 void writeEEPROM(void)
757 #ifdef USE_RX_SPI
758 rxSpiStop(); // some rx spi protocols use hardware timer, which needs to be stopped before writing to eeprom
759 #endif
760 systemConfigMutable()->configurationState = CONFIGURATION_STATE_CONFIGURED;
762 writeUnmodifiedConfigToEEPROM();
765 bool resetEEPROM(bool useCustomDefaults)
767 #if !defined(USE_CUSTOM_DEFAULTS)
768 UNUSED(useCustomDefaults);
769 #else
770 if (useCustomDefaults) {
771 if (!resetConfigToCustomDefaults()) {
772 return false;
774 } else
775 #endif
777 resetConfig();
780 writeUnmodifiedConfigToEEPROM();
782 return true;
785 void ensureEEPROMStructureIsValid(void)
787 if (isEEPROMStructureValid()) {
788 return;
790 resetEEPROM(false);
793 void saveConfigAndNotify(void)
795 // The write to EEPROM will cause a big delay in the current task, so ignore
796 schedulerIgnoreTaskExecTime();
798 writeEEPROM();
799 readEEPROM();
800 beeperConfirmationBeeps(1);
803 void setConfigDirty(void)
805 configIsDirty = true;
808 bool isConfigDirty(void)
810 return configIsDirty;
813 void changePidProfileFromCellCount(uint8_t cellCount)
815 if (currentPidProfile->auto_profile_cell_count == cellCount || currentPidProfile->auto_profile_cell_count == AUTO_PROFILE_CELL_COUNT_STAY) {
816 return;
819 unsigned profileIndex = (systemConfig()->pidProfileIndex + 1) % PID_PROFILE_COUNT;
820 int matchingProfileIndex = -1;
821 while (profileIndex != systemConfig()->pidProfileIndex) {
822 if (pidProfiles(profileIndex)->auto_profile_cell_count == cellCount) {
823 matchingProfileIndex = profileIndex;
825 break;
826 } else if (matchingProfileIndex < 0 && pidProfiles(profileIndex)->auto_profile_cell_count == AUTO_PROFILE_CELL_COUNT_STAY) {
827 matchingProfileIndex = profileIndex;
830 profileIndex = (profileIndex + 1) % PID_PROFILE_COUNT;
833 if (matchingProfileIndex >= 0) {
834 changePidProfile(matchingProfileIndex);
838 void changePidProfile(uint8_t pidProfileIndex)
840 // The config switch will cause a big enough delay in the current task to upset the scheduler
841 schedulerIgnoreTaskExecTime();
843 if (pidProfileIndex < PID_PROFILE_COUNT) {
844 systemConfigMutable()->pidProfileIndex = pidProfileIndex;
845 loadPidProfile();
847 pidInit(currentPidProfile);
848 initEscEndpoints();
849 mixerInitProfile();
852 beeperConfirmationBeeps(pidProfileIndex + 1);
855 bool isSystemConfigured(void)
857 return systemConfig()->configurationState == CONFIGURATION_STATE_CONFIGURED;
860 void setRebootRequired(void)
862 rebootRequired = true;
863 setArmingDisabled(ARMING_DISABLED_REBOOT_REQUIRED);
866 bool getRebootRequired(void)
868 return rebootRequired;