Send motor data and then immediately decode prior telemetry data for bitbanged DSHOT...
[betaflight.git] / src / main / config / config.c
blob458dfae362f858178d2543f78520c7ea11dba0b9
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/displayport_msp.h"
61 #include "io/gps.h"
62 #include "io/ledstrip.h"
63 #include "io/serial.h"
64 #include "io/vtx.h"
66 #include "msp/msp_box.h"
68 #include "osd/osd.h"
70 #include "pg/adc.h"
71 #include "pg/beeper.h"
72 #include "pg/beeper_dev.h"
73 #include "pg/displayport_profiles.h"
74 #include "pg/gyrodev.h"
75 #include "pg/motor.h"
76 #include "pg/pg.h"
77 #include "pg/pg_ids.h"
78 #include "pg/rx.h"
79 #include "pg/rx_spi.h"
80 #include "pg/sdcard.h"
81 #include "pg/vtx_table.h"
83 #include "rx/rx.h"
84 #include "rx/rx_spi.h"
86 #include "scheduler/scheduler.h"
88 #include "sensors/acceleration.h"
89 #include "sensors/battery.h"
90 #include "sensors/compass.h"
91 #include "sensors/gyro.h"
93 #include "config.h"
95 #include "drivers/dshot.h"
97 static bool configIsDirty; /* someone indicated that the config is modified and it is not yet saved */
99 static bool rebootRequired = false; // set if a config change requires a reboot to take effect
101 static bool eepromWriteInProgress = false;
103 pidProfile_t *currentPidProfile;
105 #ifndef RX_SPI_DEFAULT_PROTOCOL
106 #define RX_SPI_DEFAULT_PROTOCOL 0
107 #endif
109 PG_REGISTER_WITH_RESET_TEMPLATE(pilotConfig_t, pilotConfig, PG_PILOT_CONFIG, 2);
111 PG_RESET_TEMPLATE(pilotConfig_t, pilotConfig,
112 .craftName = { 0 },
113 .pilotName = { 0 },
116 PG_REGISTER_WITH_RESET_TEMPLATE(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 3);
118 PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
119 .pidProfileIndex = 0,
120 .activeRateProfile = 0,
121 .debug_mode = DEBUG_MODE,
122 .task_statistics = true,
123 .rateProfile6PosSwitch = false,
124 .cpu_overclock = DEFAULT_CPU_OVERCLOCK,
125 .powerOnArmingGraceTime = 5,
126 .boardIdentifier = TARGET_BOARD_IDENTIFIER,
127 .hseMhz = SYSTEM_HSE_MHZ, // Only used for F4 and G4 targets
128 .configurationState = CONFIGURATION_STATE_DEFAULTS_BARE,
129 .enableStickArming = false,
132 bool isEepromWriteInProgress(void)
134 return eepromWriteInProgress;
137 uint8_t getCurrentPidProfileIndex(void)
139 return systemConfig()->pidProfileIndex;
142 static void loadPidProfile(void)
144 currentPidProfile = pidProfilesMutable(systemConfig()->pidProfileIndex);
147 uint8_t getCurrentControlRateProfileIndex(void)
149 return systemConfig()->activeRateProfile;
152 uint16_t getCurrentMinthrottle(void)
154 return motorConfig()->minthrottle;
157 void resetConfig(void)
159 pgResetAll();
161 #if defined(USE_TARGET_CONFIG)
162 targetConfiguration();
163 #endif
166 static void activateConfig(void)
168 loadPidProfile();
169 loadControlRateProfile();
171 initRcProcessing();
173 activeAdjustmentRangeReset();
175 pidInit(currentPidProfile);
177 rcControlsInit();
179 failsafeReset();
180 #ifdef USE_ACC
181 setAccelerationTrims(&accelerometerConfigMutable()->accZero);
182 accInitFilters();
183 #endif
185 imuConfigure(throttleCorrectionConfig()->throttle_correction_angle, throttleCorrectionConfig()->throttle_correction_value);
187 #if defined(USE_LED_STRIP_STATUS_MODE)
188 reevaluateLedConfig();
189 #endif
191 initActiveBoxIds();
194 static void adjustFilterLimit(uint16_t *parm, uint16_t resetValue)
196 if (*parm > LPF_MAX_HZ) {
197 *parm = resetValue;
201 static void validateAndFixRatesSettings(void)
203 for (unsigned profileIndex = 0; profileIndex < CONTROL_RATE_PROFILE_COUNT; profileIndex++) {
204 const ratesType_e ratesType = controlRateProfilesMutable(profileIndex)->rates_type;
205 for (unsigned axis = FD_ROLL; axis <= FD_YAW; axis++) {
206 controlRateProfilesMutable(profileIndex)->rcRates[axis] = constrain(controlRateProfilesMutable(profileIndex)->rcRates[axis], 0, ratesSettingLimits[ratesType].rc_rate_limit);
207 controlRateProfilesMutable(profileIndex)->rates[axis] = constrain(controlRateProfilesMutable(profileIndex)->rates[axis], 0, ratesSettingLimits[ratesType].srate_limit);
208 controlRateProfilesMutable(profileIndex)->rcExpo[axis] = constrain(controlRateProfilesMutable(profileIndex)->rcExpo[axis], 0, ratesSettingLimits[ratesType].expo_limit);
213 static void validateAndFixConfig(void)
215 #if !defined(USE_QUAD_MIXER_ONLY)
216 // Reset unsupported mixer mode to default.
217 // This check will be gone when motor/servo mixers are loaded dynamically
218 // by configurator as a part of configuration procedure.
220 mixerMode_e mixerMode = mixerConfigMutable()->mixerMode;
222 if (!(mixerMode == MIXER_CUSTOM || mixerMode == MIXER_CUSTOM_AIRPLANE || mixerMode == MIXER_CUSTOM_TRI)) {
223 if (mixers[mixerMode].motorCount && mixers[mixerMode].motor == NULL)
224 mixerConfigMutable()->mixerMode = MIXER_CUSTOM;
225 #ifdef USE_SERVOS
226 if (mixers[mixerMode].useServo && servoMixers[mixerMode].servoRuleCount == 0)
227 mixerConfigMutable()->mixerMode = MIXER_CUSTOM_AIRPLANE;
228 #endif
230 #endif
232 if (!isSerialConfigValid(serialConfig())) {
233 pgResetFn_serialConfig(serialConfigMutable());
236 #if defined(USE_GPS)
237 const serialPortConfig_t *gpsSerial = findSerialPortConfig(FUNCTION_GPS);
238 if (gpsConfig()->provider == GPS_MSP && gpsSerial) {
239 serialRemovePort(gpsSerial->identifier);
241 #endif
242 if (
243 #if defined(USE_GPS)
244 gpsConfig()->provider != GPS_MSP && !gpsSerial &&
245 #endif
246 true) {
247 featureDisableImmediate(FEATURE_GPS);
250 for (unsigned i = 0; i < PID_PROFILE_COUNT; i++) {
251 // Fix filter settings to handle cases where an older configurator was used that
252 // allowed higher cutoff limits from previous firmware versions.
253 adjustFilterLimit(&pidProfilesMutable(i)->dterm_lpf1_static_hz, LPF_MAX_HZ);
254 adjustFilterLimit(&pidProfilesMutable(i)->dterm_lpf2_static_hz, LPF_MAX_HZ);
255 adjustFilterLimit(&pidProfilesMutable(i)->dterm_notch_hz, LPF_MAX_HZ);
256 adjustFilterLimit(&pidProfilesMutable(i)->dterm_notch_cutoff, 0);
258 // Prevent invalid notch cutoff
259 if (pidProfilesMutable(i)->dterm_notch_cutoff >= pidProfilesMutable(i)->dterm_notch_hz) {
260 pidProfilesMutable(i)->dterm_notch_hz = 0;
263 #ifdef USE_DYN_LPF
264 //Prevent invalid dynamic lowpass
265 if (pidProfilesMutable(i)->dterm_lpf1_dyn_min_hz > pidProfilesMutable(i)->dterm_lpf1_dyn_max_hz) {
266 pidProfilesMutable(i)->dterm_lpf1_dyn_min_hz = 0;
268 #endif
270 if (pidProfilesMutable(i)->motor_output_limit > 100 || pidProfilesMutable(i)->motor_output_limit == 0) {
271 pidProfilesMutable(i)->motor_output_limit = 100;
274 if (pidProfilesMutable(i)->auto_profile_cell_count > MAX_AUTO_DETECT_CELL_COUNT || pidProfilesMutable(i)->auto_profile_cell_count < AUTO_PROFILE_CELL_COUNT_CHANGE) {
275 pidProfilesMutable(i)->auto_profile_cell_count = AUTO_PROFILE_CELL_COUNT_STAY;
278 // If the d_min value for any axis is >= the D gain then reset d_min to 0 for consistent Configurator behavior
279 for (unsigned axis = 0; axis <= FD_YAW; axis++) {
280 if (pidProfilesMutable(i)->d_min[axis] > pidProfilesMutable(i)->pid[axis].D) {
281 pidProfilesMutable(i)->d_min[axis] = 0;
285 #if defined(USE_BATTERY_VOLTAGE_SAG_COMPENSATION)
286 if (batteryConfig()->voltageMeterSource != VOLTAGE_METER_ADC) {
287 pidProfilesMutable(i)->vbat_sag_compensation = 0;
289 #endif
292 if (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_BRUSHED) {
293 featureDisableImmediate(FEATURE_3D);
295 if (motorConfig()->mincommand < 1000) {
296 motorConfigMutable()->mincommand = 1000;
300 if ((motorConfig()->dev.motorPwmProtocol == PWM_TYPE_STANDARD) && (motorConfig()->dev.motorPwmRate > BRUSHLESS_MOTORS_PWM_RATE)) {
301 motorConfigMutable()->dev.motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE;
304 validateAndFixGyroConfig();
306 #if defined(USE_MAG)
307 buildAlignmentFromStandardAlignment(&compassConfigMutable()->mag_customAlignment, compassConfig()->mag_alignment);
308 #endif
309 buildAlignmentFromStandardAlignment(&gyroDeviceConfigMutable(0)->customAlignment, gyroDeviceConfig(0)->alignment);
310 #if defined(USE_MULTI_GYRO)
311 buildAlignmentFromStandardAlignment(&gyroDeviceConfigMutable(1)->customAlignment, gyroDeviceConfig(1)->alignment);
312 #endif
314 #ifdef USE_ACC
315 if (accelerometerConfig()->accZero.values.roll != 0 ||
316 accelerometerConfig()->accZero.values.pitch != 0 ||
317 accelerometerConfig()->accZero.values.yaw != 0) {
318 accelerometerConfigMutable()->accZero.values.calibrationCompleted = 1;
320 #endif // USE_ACC
322 if (!(featureIsConfigured(FEATURE_RX_PARALLEL_PWM) || featureIsConfigured(FEATURE_RX_PPM) || featureIsConfigured(FEATURE_RX_SERIAL) || featureIsConfigured(FEATURE_RX_MSP) || featureIsConfigured(FEATURE_RX_SPI))) {
323 featureEnableImmediate(DEFAULT_RX_FEATURE);
326 if (featureIsConfigured(FEATURE_RX_PPM)) {
327 featureDisableImmediate(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_SPI);
330 if (featureIsConfigured(FEATURE_RX_MSP)) {
331 featureDisableImmediate(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_SPI);
334 if (featureIsConfigured(FEATURE_RX_SERIAL)) {
335 featureDisableImmediate(FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
338 #ifdef USE_RX_SPI
339 if (featureIsConfigured(FEATURE_RX_SPI)) {
340 featureDisableImmediate(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_MSP);
342 #endif // USE_RX_SPI
344 if (featureIsConfigured(FEATURE_RX_PARALLEL_PWM)) {
345 featureDisableImmediate(FEATURE_RX_SERIAL | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
348 #if defined(USE_ADC)
349 if (featureIsConfigured(FEATURE_RSSI_ADC)) {
350 rxConfigMutable()->rssi_channel = 0;
351 rxConfigMutable()->rssi_src_frame_errors = false;
352 } else
353 #endif
354 if (rxConfigMutable()->rssi_channel
355 #if defined(USE_RX_PWM) || defined(USE_RX_PPM)
356 || featureIsConfigured(FEATURE_RX_PPM) || featureIsConfigured(FEATURE_RX_PARALLEL_PWM)
357 #endif
359 rxConfigMutable()->rssi_src_frame_errors = false;
362 if (
363 featureIsConfigured(FEATURE_3D) || !featureIsConfigured(FEATURE_GPS) || mixerModeIsFixedWing(mixerConfig()->mixerMode)
364 #if !defined(USE_GPS) || !defined(USE_GPS_RESCUE)
365 || true
366 #endif
369 #ifdef USE_GPS_RESCUE
370 if (failsafeConfig()->failsafe_procedure == FAILSAFE_PROCEDURE_GPS_RESCUE) {
371 failsafeConfigMutable()->failsafe_procedure = FAILSAFE_PROCEDURE_DROP_IT;
373 #endif
375 if (isModeActivationConditionPresent(BOXGPSRESCUE)) {
376 removeModeActivationCondition(BOXGPSRESCUE);
380 #if defined(USE_ESC_SENSOR)
381 if (!findSerialPortConfig(FUNCTION_ESC_SENSOR)) {
382 featureDisableImmediate(FEATURE_ESC_SENSOR);
384 #endif
386 for (int i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
387 const modeActivationCondition_t *mac = modeActivationConditions(i);
389 if (mac->linkedTo) {
390 if (mac->modeId == BOXARM || isModeActivationConditionLinked(mac->linkedTo)) {
391 removeModeActivationCondition(mac->modeId);
396 #if defined(USE_DSHOT_TELEMETRY) && defined(USE_DSHOT_BITBANG)
397 if (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_PROSHOT1000 && motorConfig()->dev.useDshotTelemetry &&
398 motorConfig()->dev.useDshotBitbang == DSHOT_BITBANG_ON) {
399 motorConfigMutable()->dev.useDshotBitbang = DSHOT_BITBANG_AUTO;
401 #endif
403 #ifdef USE_ADC
404 adcConfigMutable()->vbat.enabled = (batteryConfig()->voltageMeterSource == VOLTAGE_METER_ADC);
405 adcConfigMutable()->current.enabled = (batteryConfig()->currentMeterSource == CURRENT_METER_ADC);
407 // The FrSky D SPI RX sends RSSI_ADC_PIN (if configured) as A2
408 adcConfigMutable()->rssi.enabled = featureIsEnabled(FEATURE_RSSI_ADC);
409 #ifdef USE_RX_SPI
410 adcConfigMutable()->rssi.enabled |= (featureIsEnabled(FEATURE_RX_SPI) && rxSpiConfig()->rx_spi_protocol == RX_SPI_FRSKY_D);
411 #endif
412 #endif // USE_ADC
415 // clear features that are not supported.
416 // I have kept them all here in one place, some could be moved to sections of code above.
418 #ifndef USE_RX_PPM
419 featureDisableImmediate(FEATURE_RX_PPM);
420 #endif
422 #ifndef USE_SERIALRX
423 featureDisableImmediate(FEATURE_RX_SERIAL);
424 #endif
426 #if !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL2)
427 featureDisableImmediate(FEATURE_SOFTSERIAL);
428 #endif
430 #ifndef USE_RANGEFINDER
431 featureDisableImmediate(FEATURE_RANGEFINDER);
432 #endif
434 #ifndef USE_TELEMETRY
435 featureDisableImmediate(FEATURE_TELEMETRY);
436 #endif
438 #ifndef USE_PWM
439 featureDisableImmediate(FEATURE_RX_PARALLEL_PWM);
440 #endif
442 #ifndef USE_RX_MSP
443 featureDisableImmediate(FEATURE_RX_MSP);
444 #endif
446 #ifndef USE_LED_STRIP
447 featureDisableImmediate(FEATURE_LED_STRIP);
448 #endif
450 #ifndef USE_DASHBOARD
451 featureDisableImmediate(FEATURE_DASHBOARD);
452 #endif
454 #ifndef USE_OSD
455 featureDisableImmediate(FEATURE_OSD);
456 #endif
458 #ifndef USE_SERVOS
459 featureDisableImmediate(FEATURE_SERVO_TILT | FEATURE_CHANNEL_FORWARDING);
460 #endif
462 #ifndef USE_TRANSPONDER
463 featureDisableImmediate(FEATURE_TRANSPONDER);
464 #endif
466 #ifndef USE_RX_SPI
467 featureDisableImmediate(FEATURE_RX_SPI);
468 #endif
470 #ifndef USE_ESC_SENSOR
471 featureDisableImmediate(FEATURE_ESC_SENSOR);
472 #endif
474 #if !defined(USE_ADC)
475 featureDisableImmediate(FEATURE_RSSI_ADC);
476 #endif
478 // Enable features in Cloud Build
479 #ifdef CLOUD_BUILD
481 if (systemConfig()->configurationState == CONFIGURATION_STATE_DEFAULTS_BARE) {
483 #ifdef USE_DASHBOARD
484 featureEnableImmediate(FEATURE_DASHBOARD);
485 #endif
486 #ifdef USE_GPS
487 featureEnableImmediate(FEATURE_GPS);
488 #endif
489 #ifdef USE_LED_STRIP
490 featureEnableImmediate(FEATURE_LED_STRIP);
491 #endif
492 #ifdef USE_OSD
493 featureEnableImmediate(FEATURE_OSD);
494 #endif
495 #ifdef USE_RANGEFINDER
496 featureEnableImmediate(FEATURE_RANGEFINDER);
497 #endif
498 #ifdef USE_SERVOS
499 featureEnableImmediate(FEATURE_CHANNEL_FORWARDING);
500 featureEnableImmediate(FEATURE_SERVO_TILT);
501 #endif
502 #ifdef USE_TELEMETRY
503 featureEnableImmediate(FEATURE_TELEMETRY);
504 #endif
505 #ifdef USE_TRANSPONDER
506 featureEnableImmediate(FEATURE_TRANSPONDER);
507 #endif
511 #endif // CLOUD_BUILD
514 #if defined(USE_BEEPER)
515 #ifdef USE_TIMER
516 if (beeperDevConfig()->frequency && !timerGetConfiguredByTag(beeperDevConfig()->ioTag)) {
517 beeperDevConfigMutable()->frequency = 0;
519 #endif
521 if (beeperConfig()->beeper_off_flags & ~BEEPER_ALLOWED_MODES) {
522 beeperConfigMutable()->beeper_off_flags = 0;
525 #ifdef USE_DSHOT
526 if (beeperConfig()->dshotBeaconOffFlags & ~DSHOT_BEACON_ALLOWED_MODES) {
527 beeperConfigMutable()->dshotBeaconOffFlags = 0;
530 if (beeperConfig()->dshotBeaconTone < DSHOT_CMD_BEACON1
531 || beeperConfig()->dshotBeaconTone > DSHOT_CMD_BEACON5) {
532 beeperConfigMutable()->dshotBeaconTone = DSHOT_CMD_BEACON1;
534 #endif
535 #endif
537 bool configuredMotorProtocolDshot = false;
538 checkMotorProtocolEnabled(&motorConfig()->dev, &configuredMotorProtocolDshot);
539 #if defined(USE_DSHOT)
540 // If using DSHOT protocol disable unsynched PWM as it's meaningless
541 if (configuredMotorProtocolDshot) {
542 motorConfigMutable()->dev.useUnsyncedPwm = false;
545 #if defined(USE_DSHOT_TELEMETRY)
546 bool nChannelTimerUsed = false;
547 for (unsigned i = 0; i < getMotorCount(); i++) {
548 const ioTag_t tag = motorConfig()->dev.ioTags[i];
549 if (tag) {
550 const timerHardware_t *timer = timerGetConfiguredByTag(tag);
551 if (timer && timer->output & TIMER_OUTPUT_N_CHANNEL) {
552 nChannelTimerUsed = true;
554 break;
559 if ((!configuredMotorProtocolDshot || (motorConfig()->dev.useDshotBitbang == DSHOT_BITBANG_OFF && (motorConfig()->dev.useBurstDshot == DSHOT_DMAR_ON || nChannelTimerUsed))) && motorConfig()->dev.useDshotTelemetry) {
560 motorConfigMutable()->dev.useDshotTelemetry = false;
562 #endif // USE_DSHOT_TELEMETRY
563 #endif // USE_DSHOT
565 #if defined(USE_OSD)
566 for (int i = 0; i < OSD_TIMER_COUNT; i++) {
567 const uint16_t t = osdConfig()->timers[i];
568 if (OSD_TIMER_SRC(t) >= OSD_TIMER_SRC_COUNT ||
569 OSD_TIMER_PRECISION(t) >= OSD_TIMER_PREC_COUNT) {
570 osdConfigMutable()->timers[i] = osdTimerDefault[i];
573 #endif
575 #if defined(USE_VTX_COMMON) && defined(USE_VTX_TABLE)
576 // reset vtx band, channel, power if outside range specified by vtxtable
577 if (vtxSettingsConfig()->channel > vtxTableConfig()->channels) {
578 vtxSettingsConfigMutable()->channel = 0;
579 if (vtxSettingsConfig()->band > 0) {
580 vtxSettingsConfigMutable()->freq = 0; // band/channel determined frequency can't be valid anymore
583 if (vtxSettingsConfig()->band > vtxTableConfig()->bands) {
584 vtxSettingsConfigMutable()->band = 0;
585 vtxSettingsConfigMutable()->freq = 0; // band/channel determined frequency can't be valid anymore
587 if (vtxSettingsConfig()->power > vtxTableConfig()->powerLevels) {
588 vtxSettingsConfigMutable()->power = 0;
590 #endif
592 validateAndFixRatesSettings(); // constrain the various rates settings to limits imposed by the rates type
594 #if defined(USE_RX_MSP_OVERRIDE)
595 if (!rxConfig()->msp_override_channels_mask) {
596 removeModeActivationCondition(BOXMSPOVERRIDE);
599 for (int i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
600 const modeActivationCondition_t *mac = modeActivationConditions(i);
601 if (mac->modeId == BOXMSPOVERRIDE && ((1 << (mac->auxChannelIndex) & (rxConfig()->msp_override_channels_mask)))) {
602 rxConfigMutable()->msp_override_channels_mask &= ~(1 << (mac->auxChannelIndex + NON_AUX_CHANNEL_COUNT));
605 #endif
607 validateAndfixMotorOutputReordering(motorConfigMutable()->dev.motorOutputReordering, MAX_SUPPORTED_MOTORS);
609 // validate that the minimum battery cell voltage is less than the maximum cell voltage
610 // reset to defaults if not
611 if (batteryConfig()->vbatmincellvoltage >= batteryConfig()->vbatmaxcellvoltage) {
612 batteryConfigMutable()->vbatmincellvoltage = VBAT_CELL_VOLTAGE_DEFAULT_MIN;
613 batteryConfigMutable()->vbatmaxcellvoltage = VBAT_CELL_VOLTAGE_DEFAULT_MAX;
616 #ifdef USE_MSP_DISPLAYPORT
617 // Find the first serial port on which MSP Displayport is enabled
618 displayPortMspSetSerial(SERIAL_PORT_NONE);
620 for (uint8_t serialPort = 0; serialPort < SERIAL_PORT_COUNT; serialPort++) {
621 const serialPortConfig_t *portConfig = &serialConfig()->portConfigs[serialPort];
623 if (portConfig &&
624 (portConfig->identifier != SERIAL_PORT_USB_VCP) &&
625 ((portConfig->functionMask & (FUNCTION_VTX_MSP | FUNCTION_MSP)) == (FUNCTION_VTX_MSP | FUNCTION_MSP))) {
626 displayPortMspSetSerial(portConfig->identifier);
627 break;
630 #endif
632 #ifdef USE_BLACKBOX
633 validateAndFixBlackBox();
634 #endif // USE_BLACKBOX
636 #if defined(TARGET_VALIDATECONFIG)
637 // This should be done at the end of the validation
638 targetValidateConfiguration();
639 #endif
642 void validateAndFixGyroConfig(void)
644 // Fix gyro filter settings to handle cases where an older configurator was used that
645 // allowed higher cutoff limits from previous firmware versions.
646 adjustFilterLimit(&gyroConfigMutable()->gyro_lpf1_static_hz, LPF_MAX_HZ);
647 adjustFilterLimit(&gyroConfigMutable()->gyro_lpf2_static_hz, LPF_MAX_HZ);
648 adjustFilterLimit(&gyroConfigMutable()->gyro_soft_notch_hz_1, LPF_MAX_HZ);
649 adjustFilterLimit(&gyroConfigMutable()->gyro_soft_notch_cutoff_1, 0);
650 adjustFilterLimit(&gyroConfigMutable()->gyro_soft_notch_hz_2, LPF_MAX_HZ);
651 adjustFilterLimit(&gyroConfigMutable()->gyro_soft_notch_cutoff_2, 0);
653 // Prevent invalid notch cutoff
654 if (gyroConfig()->gyro_soft_notch_cutoff_1 >= gyroConfig()->gyro_soft_notch_hz_1) {
655 gyroConfigMutable()->gyro_soft_notch_hz_1 = 0;
657 if (gyroConfig()->gyro_soft_notch_cutoff_2 >= gyroConfig()->gyro_soft_notch_hz_2) {
658 gyroConfigMutable()->gyro_soft_notch_hz_2 = 0;
660 #ifdef USE_DYN_LPF
661 //Prevent invalid dynamic lowpass filter
662 if (gyroConfig()->gyro_lpf1_dyn_min_hz > gyroConfig()->gyro_lpf1_dyn_max_hz) {
663 gyroConfigMutable()->gyro_lpf1_dyn_min_hz = 0;
665 #endif
667 if (gyro.sampleRateHz > 0) {
668 float samplingTime = 1.0f / gyro.sampleRateHz;
670 // check for looptime restrictions based on motor protocol. Motor times have safety margin
671 float motorUpdateRestriction;
673 #if defined(STM32F4) || defined(STM32G4)
674 /* If bidirectional DSHOT is being used on an F4 or G4 then force DSHOT300. The motor update restrictions then applied
675 * will automatically consider the loop time and adjust pid_process_denom appropriately
677 if (motorConfig()->dev.useDshotTelemetry && (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_DSHOT600)) {
678 motorConfigMutable()->dev.motorPwmProtocol = PWM_TYPE_DSHOT300;
680 #endif
682 switch (motorConfig()->dev.motorPwmProtocol) {
683 case PWM_TYPE_STANDARD:
684 motorUpdateRestriction = 1.0f / BRUSHLESS_MOTORS_PWM_RATE;
685 break;
686 case PWM_TYPE_ONESHOT125:
687 motorUpdateRestriction = 0.0005f;
688 break;
689 case PWM_TYPE_ONESHOT42:
690 motorUpdateRestriction = 0.0001f;
691 break;
692 #ifdef USE_DSHOT
693 case PWM_TYPE_DSHOT150:
694 motorUpdateRestriction = 0.000250f;
695 break;
696 case PWM_TYPE_DSHOT300:
697 motorUpdateRestriction = 0.0001f;
698 break;
699 #endif
700 default:
701 motorUpdateRestriction = 0.00003125f;
702 break;
705 if (motorConfig()->dev.useUnsyncedPwm) {
706 bool configuredMotorProtocolDshot = false;
707 checkMotorProtocolEnabled(&motorConfig()->dev, &configuredMotorProtocolDshot);
708 // Prevent overriding the max rate of motors
709 if (!configuredMotorProtocolDshot && motorConfig()->dev.motorPwmProtocol != PWM_TYPE_STANDARD) {
710 const uint32_t maxEscRate = lrintf(1.0f / motorUpdateRestriction);
711 motorConfigMutable()->dev.motorPwmRate = MIN(motorConfig()->dev.motorPwmRate, maxEscRate);
713 } else {
714 const float pidLooptime = samplingTime * pidConfig()->pid_process_denom;
715 if (motorConfig()->dev.useDshotTelemetry) {
716 motorUpdateRestriction *= 2;
718 if (pidLooptime < motorUpdateRestriction) {
719 uint8_t minPidProcessDenom = motorUpdateRestriction / samplingTime;
720 if (motorUpdateRestriction / samplingTime > minPidProcessDenom) {
721 // if any fractional part then round up
722 minPidProcessDenom++;
724 minPidProcessDenom = constrain(minPidProcessDenom, 1, MAX_PID_PROCESS_DENOM);
725 pidConfigMutable()->pid_process_denom = MAX(pidConfigMutable()->pid_process_denom, minPidProcessDenom);
730 if (systemConfig()->activeRateProfile >= CONTROL_RATE_PROFILE_COUNT) {
731 systemConfigMutable()->activeRateProfile = 0;
733 loadControlRateProfile();
735 if (systemConfig()->pidProfileIndex >= PID_PROFILE_COUNT) {
736 systemConfigMutable()->pidProfileIndex = 0;
738 loadPidProfile();
741 #ifdef USE_BLACKBOX
742 void validateAndFixBlackBox(void) {
743 #ifndef USE_FLASHFS
744 if (blackboxConfig()->device == BLACKBOX_DEVICE_FLASH) {
745 blackboxConfigMutable()->device = BLACKBOX_DEVICE_NONE;
747 #endif // USE_FLASHFS
749 if (blackboxConfig()->device == BLACKBOX_DEVICE_SDCARD) {
750 #if defined(USE_SDCARD)
751 if (!sdcardConfig()->mode)
752 #endif
754 blackboxConfigMutable()->device = BLACKBOX_DEVICE_NONE;
758 #endif // USE_BLACKBOX
760 bool readEEPROM(void)
762 suspendRxSignal();
764 // Sanity check, read flash
765 bool success = loadEEPROM();
767 featureInit();
769 validateAndFixConfig();
771 activateConfig();
773 resumeRxSignal();
775 return success;
778 void writeUnmodifiedConfigToEEPROM(void)
780 validateAndFixConfig();
782 suspendRxSignal();
783 eepromWriteInProgress = true;
784 writeConfigToEEPROM();
785 eepromWriteInProgress = false;
786 resumeRxSignal();
787 configIsDirty = false;
790 void writeEEPROM(void)
792 #ifdef USE_RX_SPI
793 rxSpiStop(); // some rx spi protocols use hardware timer, which needs to be stopped before writing to eeprom
794 #endif
795 systemConfigMutable()->configurationState = CONFIGURATION_STATE_CONFIGURED;
797 writeUnmodifiedConfigToEEPROM();
800 bool resetEEPROM(void)
802 resetConfig();
804 writeUnmodifiedConfigToEEPROM();
806 return true;
809 void ensureEEPROMStructureIsValid(void)
811 if (isEEPROMStructureValid()) {
812 return;
814 resetEEPROM();
817 void saveConfigAndNotify(void)
819 // The write to EEPROM will cause a big delay in the current task, so ignore
820 schedulerIgnoreTaskExecTime();
822 writeEEPROM();
823 readEEPROM();
824 beeperConfirmationBeeps(1);
827 void setConfigDirty(void)
829 configIsDirty = true;
832 bool isConfigDirty(void)
834 return configIsDirty;
837 void changePidProfileFromCellCount(uint8_t cellCount)
839 if (currentPidProfile->auto_profile_cell_count == cellCount || currentPidProfile->auto_profile_cell_count == AUTO_PROFILE_CELL_COUNT_STAY) {
840 return;
843 unsigned profileIndex = (systemConfig()->pidProfileIndex + 1) % PID_PROFILE_COUNT;
844 int matchingProfileIndex = -1;
845 while (profileIndex != systemConfig()->pidProfileIndex) {
846 if (pidProfiles(profileIndex)->auto_profile_cell_count == cellCount) {
847 matchingProfileIndex = profileIndex;
849 break;
850 } else if (matchingProfileIndex < 0 && pidProfiles(profileIndex)->auto_profile_cell_count == AUTO_PROFILE_CELL_COUNT_STAY) {
851 matchingProfileIndex = profileIndex;
854 profileIndex = (profileIndex + 1) % PID_PROFILE_COUNT;
857 if (matchingProfileIndex >= 0) {
858 changePidProfile(matchingProfileIndex);
862 void changePidProfile(uint8_t pidProfileIndex)
864 // The config switch will cause a big enough delay in the current task to upset the scheduler
865 schedulerIgnoreTaskExecTime();
867 if (pidProfileIndex < PID_PROFILE_COUNT) {
868 systemConfigMutable()->pidProfileIndex = pidProfileIndex;
869 loadPidProfile();
871 pidInit(currentPidProfile);
872 initEscEndpoints();
873 mixerInitProfile();
876 beeperConfirmationBeeps(pidProfileIndex + 1);
879 bool isSystemConfigured(void)
881 return systemConfig()->configurationState == CONFIGURATION_STATE_CONFIGURED;
884 void setRebootRequired(void)
886 rebootRequired = true;
887 setArmingDisabled(ARMING_DISABLED_REBOOT_REQUIRED);
890 bool getRebootRequired(void)
892 return rebootRequired;