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)
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/>.
28 #include "blackbox/blackbox.h"
30 #include "build/debug.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"
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"
62 #include "io/ledstrip.h"
63 #include "io/serial.h"
66 #include "msp/msp_box.h"
71 #include "pg/beeper.h"
72 #include "pg/beeper_dev.h"
73 #include "pg/displayport_profiles.h"
74 #include "pg/gyrodev.h"
77 #include "pg/pg_ids.h"
79 #include "pg/rx_spi.h"
80 #include "pg/sdcard.h"
81 #include "pg/vtx_table.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"
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
109 PG_REGISTER_WITH_RESET_TEMPLATE(pilotConfig_t
, pilotConfig
, PG_PILOT_CONFIG
, 2);
111 PG_RESET_TEMPLATE(pilotConfig_t
, pilotConfig
,
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)
161 #if defined(USE_TARGET_CONFIG)
162 targetConfiguration();
166 static void activateConfig(void)
169 loadControlRateProfile();
173 activeAdjustmentRangeReset();
175 pidInit(currentPidProfile
);
181 setAccelerationTrims(&accelerometerConfigMutable()->accZero
);
185 imuConfigure(throttleCorrectionConfig()->throttle_correction_angle
, throttleCorrectionConfig()->throttle_correction_value
);
187 #if defined(USE_LED_STRIP_STATUS_MODE)
188 reevaluateLedConfig();
194 static void adjustFilterLimit(uint16_t *parm
, uint16_t resetValue
)
196 if (*parm
> LPF_MAX_HZ
) {
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
;
226 if (mixers
[mixerMode
].useServo
&& servoMixers
[mixerMode
].servoRuleCount
== 0)
227 mixerConfigMutable()->mixerMode
= MIXER_CUSTOM_AIRPLANE
;
232 if (!isSerialConfigValid(serialConfig())) {
233 pgResetFn_serialConfig(serialConfigMutable());
237 const serialPortConfig_t
*gpsSerial
= findSerialPortConfig(FUNCTION_GPS
);
238 if (gpsConfig()->provider
== GPS_MSP
&& gpsSerial
) {
239 serialRemovePort(gpsSerial
->identifier
);
244 gpsConfig()->provider
!= GPS_MSP
&& !gpsSerial
&&
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;
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;
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;
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();
307 buildAlignmentFromStandardAlignment(&compassConfigMutable()->mag_customAlignment
, compassConfig()->mag_alignment
);
309 buildAlignmentFromStandardAlignment(&gyroDeviceConfigMutable(0)->customAlignment
, gyroDeviceConfig(0)->alignment
);
310 #if defined(USE_MULTI_GYRO)
311 buildAlignmentFromStandardAlignment(&gyroDeviceConfigMutable(1)->customAlignment
, gyroDeviceConfig(1)->alignment
);
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;
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
);
339 if (featureIsConfigured(FEATURE_RX_SPI
)) {
340 featureDisableImmediate(FEATURE_RX_SERIAL
| FEATURE_RX_PARALLEL_PWM
| FEATURE_RX_PPM
| FEATURE_RX_MSP
);
344 if (featureIsConfigured(FEATURE_RX_PARALLEL_PWM
)) {
345 featureDisableImmediate(FEATURE_RX_SERIAL
| FEATURE_RX_MSP
| FEATURE_RX_PPM
| FEATURE_RX_SPI
);
349 if (featureIsConfigured(FEATURE_RSSI_ADC
)) {
350 rxConfigMutable()->rssi_channel
= 0;
351 rxConfigMutable()->rssi_src_frame_errors
= false;
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
)
359 rxConfigMutable()->rssi_src_frame_errors
= false;
363 featureIsConfigured(FEATURE_3D
) || !featureIsConfigured(FEATURE_GPS
) || mixerModeIsFixedWing(mixerConfig()->mixerMode
)
364 #if !defined(USE_GPS) || !defined(USE_GPS_RESCUE)
369 #ifdef USE_GPS_RESCUE
370 if (failsafeConfig()->failsafe_procedure
== FAILSAFE_PROCEDURE_GPS_RESCUE
) {
371 failsafeConfigMutable()->failsafe_procedure
= FAILSAFE_PROCEDURE_DROP_IT
;
375 if (isModeActivationConditionPresent(BOXGPSRESCUE
)) {
376 removeModeActivationCondition(BOXGPSRESCUE
);
380 #if defined(USE_ESC_SENSOR)
381 if (!findSerialPortConfig(FUNCTION_ESC_SENSOR
)) {
382 featureDisableImmediate(FEATURE_ESC_SENSOR
);
386 for (int i
= 0; i
< MAX_MODE_ACTIVATION_CONDITION_COUNT
; i
++) {
387 const modeActivationCondition_t
*mac
= modeActivationConditions(i
);
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
;
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
);
410 adcConfigMutable()->rssi
.enabled
|= (featureIsEnabled(FEATURE_RX_SPI
) && rxSpiConfig()->rx_spi_protocol
== RX_SPI_FRSKY_D
);
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.
419 featureDisableImmediate(FEATURE_RX_PPM
);
423 featureDisableImmediate(FEATURE_RX_SERIAL
);
426 #if !defined(USE_SOFTSERIAL)
427 featureDisableImmediate(FEATURE_SOFTSERIAL
);
430 #ifndef USE_RANGEFINDER
431 featureDisableImmediate(FEATURE_RANGEFINDER
);
434 #ifndef USE_TELEMETRY
435 featureDisableImmediate(FEATURE_TELEMETRY
);
439 featureDisableImmediate(FEATURE_RX_PARALLEL_PWM
);
443 featureDisableImmediate(FEATURE_RX_MSP
);
446 #ifndef USE_LED_STRIP
447 featureDisableImmediate(FEATURE_LED_STRIP
);
450 #ifndef USE_DASHBOARD
451 featureDisableImmediate(FEATURE_DASHBOARD
);
455 featureDisableImmediate(FEATURE_OSD
);
459 featureDisableImmediate(FEATURE_SERVO_TILT
| FEATURE_CHANNEL_FORWARDING
);
462 #ifndef USE_TRANSPONDER
463 featureDisableImmediate(FEATURE_TRANSPONDER
);
467 featureDisableImmediate(FEATURE_RX_SPI
);
470 #ifndef USE_ESC_SENSOR
471 featureDisableImmediate(FEATURE_ESC_SENSOR
);
474 #if !defined(USE_ADC)
475 featureDisableImmediate(FEATURE_RSSI_ADC
);
478 // Enable features in Cloud Build
481 if (systemConfig()->configurationState
== CONFIGURATION_STATE_DEFAULTS_BARE
) {
484 featureEnableImmediate(FEATURE_DASHBOARD
);
487 featureEnableImmediate(FEATURE_GPS
);
490 featureEnableImmediate(FEATURE_LED_STRIP
);
493 featureEnableImmediate(FEATURE_OSD
);
495 #ifdef USE_RANGEFINDER
496 featureEnableImmediate(FEATURE_RANGEFINDER
);
499 featureEnableImmediate(FEATURE_CHANNEL_FORWARDING
);
500 featureEnableImmediate(FEATURE_SERVO_TILT
);
502 #if defined(SOFTSERIAL1_RX_PIN) || defined(SOFTSERIAL2_RX_PIN) || defined(SOFTSERIAL1_TX_PIN) || defined(SOFTSERIAL2_TX_PIN)
503 featureEnableImmediate(FEATURE_SOFTSERIAL
);
506 featureEnableImmediate(FEATURE_TELEMETRY
);
508 #ifdef USE_TRANSPONDER
509 featureEnableImmediate(FEATURE_TRANSPONDER
);
514 #endif // CLOUD_BUILD
517 #if defined(USE_BEEPER)
519 if (beeperDevConfig()->frequency
&& !timerGetConfiguredByTag(beeperDevConfig()->ioTag
)) {
520 beeperDevConfigMutable()->frequency
= 0;
524 if (beeperConfig()->beeper_off_flags
& ~BEEPER_ALLOWED_MODES
) {
525 beeperConfigMutable()->beeper_off_flags
= 0;
529 if (beeperConfig()->dshotBeaconOffFlags
& ~DSHOT_BEACON_ALLOWED_MODES
) {
530 beeperConfigMutable()->dshotBeaconOffFlags
= DEFAULT_DSHOT_BEACON_OFF_FLAGS
;
533 if (beeperConfig()->dshotBeaconTone
< DSHOT_CMD_BEACON1
534 || beeperConfig()->dshotBeaconTone
> DSHOT_CMD_BEACON5
) {
535 beeperConfigMutable()->dshotBeaconTone
= DSHOT_CMD_BEACON1
;
540 bool configuredMotorProtocolDshot
= false;
541 checkMotorProtocolEnabled(&motorConfig()->dev
, &configuredMotorProtocolDshot
);
542 #if defined(USE_DSHOT)
543 // If using DSHOT protocol disable unsynched PWM as it's meaningless
544 if (configuredMotorProtocolDshot
) {
545 motorConfigMutable()->dev
.useUnsyncedPwm
= false;
548 #if defined(USE_DSHOT_TELEMETRY)
549 bool nChannelTimerUsed
= false;
550 for (unsigned i
= 0; i
< getMotorCount(); i
++) {
551 const ioTag_t tag
= motorConfig()->dev
.ioTags
[i
];
553 const timerHardware_t
*timer
= timerGetConfiguredByTag(tag
);
554 if (timer
&& timer
->output
& TIMER_OUTPUT_N_CHANNEL
) {
555 nChannelTimerUsed
= true;
562 if ((!configuredMotorProtocolDshot
|| (motorConfig()->dev
.useDshotBitbang
== DSHOT_BITBANG_OFF
&& (motorConfig()->dev
.useBurstDshot
== DSHOT_DMAR_ON
|| nChannelTimerUsed
))) && motorConfig()->dev
.useDshotTelemetry
) {
563 motorConfigMutable()->dev
.useDshotTelemetry
= false;
565 #endif // USE_DSHOT_TELEMETRY
569 for (int i
= 0; i
< OSD_TIMER_COUNT
; i
++) {
570 const uint16_t t
= osdConfig()->timers
[i
];
571 if (OSD_TIMER_SRC(t
) >= OSD_TIMER_SRC_COUNT
||
572 OSD_TIMER_PRECISION(t
) >= OSD_TIMER_PREC_COUNT
) {
573 osdConfigMutable()->timers
[i
] = osdTimerDefault
[i
];
578 #if defined(USE_VTX_COMMON) && defined(USE_VTX_TABLE)
579 // reset vtx band, channel, power if outside range specified by vtxtable
580 if (vtxSettingsConfig()->channel
> vtxTableConfig()->channels
) {
581 vtxSettingsConfigMutable()->channel
= 0;
582 if (vtxSettingsConfig()->band
> 0) {
583 vtxSettingsConfigMutable()->freq
= 0; // band/channel determined frequency can't be valid anymore
586 if (vtxSettingsConfig()->band
> vtxTableConfig()->bands
) {
587 vtxSettingsConfigMutable()->band
= 0;
588 vtxSettingsConfigMutable()->freq
= 0; // band/channel determined frequency can't be valid anymore
590 if (vtxSettingsConfig()->power
> vtxTableConfig()->powerLevels
) {
591 vtxSettingsConfigMutable()->power
= 0;
595 validateAndFixRatesSettings(); // constrain the various rates settings to limits imposed by the rates type
597 #if defined(USE_RX_MSP_OVERRIDE)
598 if (!rxConfig()->msp_override_channels_mask
) {
599 removeModeActivationCondition(BOXMSPOVERRIDE
);
602 for (int i
= 0; i
< MAX_MODE_ACTIVATION_CONDITION_COUNT
; i
++) {
603 const modeActivationCondition_t
*mac
= modeActivationConditions(i
);
604 if (mac
->modeId
== BOXMSPOVERRIDE
&& ((1 << (mac
->auxChannelIndex
+ NON_AUX_CHANNEL_COUNT
) & (rxConfig()->msp_override_channels_mask
)))) {
605 rxConfigMutable()->msp_override_channels_mask
&= ~(1 << (mac
->auxChannelIndex
+ NON_AUX_CHANNEL_COUNT
));
610 validateAndfixMotorOutputReordering(motorConfigMutable()->dev
.motorOutputReordering
, MAX_SUPPORTED_MOTORS
);
612 // validate that the minimum battery cell voltage is less than the maximum cell voltage
613 // reset to defaults if not
614 if (batteryConfig()->vbatmincellvoltage
>= batteryConfig()->vbatmaxcellvoltage
) {
615 batteryConfigMutable()->vbatmincellvoltage
= VBAT_CELL_VOLTAGE_DEFAULT_MIN
;
616 batteryConfigMutable()->vbatmaxcellvoltage
= VBAT_CELL_VOLTAGE_DEFAULT_MAX
;
619 #ifdef USE_MSP_DISPLAYPORT
620 // Find the first serial port on which MSP Displayport is enabled
621 displayPortMspSetSerial(SERIAL_PORT_NONE
);
623 for (uint8_t serialPort
= 0; serialPort
< SERIAL_PORT_COUNT
; serialPort
++) {
624 const serialPortConfig_t
*portConfig
= &serialConfig()->portConfigs
[serialPort
];
627 (portConfig
->identifier
!= SERIAL_PORT_USB_VCP
) &&
628 ((portConfig
->functionMask
& (FUNCTION_VTX_MSP
| FUNCTION_MSP
)) == (FUNCTION_VTX_MSP
| FUNCTION_MSP
))) {
629 displayPortMspSetSerial(portConfig
->identifier
);
636 validateAndFixBlackBox();
637 #endif // USE_BLACKBOX
639 #if defined(TARGET_VALIDATECONFIG)
640 // This should be done at the end of the validation
641 targetValidateConfiguration();
645 void validateAndFixGyroConfig(void)
647 // Fix gyro filter settings to handle cases where an older configurator was used that
648 // allowed higher cutoff limits from previous firmware versions.
649 adjustFilterLimit(&gyroConfigMutable()->gyro_lpf1_static_hz
, LPF_MAX_HZ
);
650 adjustFilterLimit(&gyroConfigMutable()->gyro_lpf2_static_hz
, LPF_MAX_HZ
);
651 adjustFilterLimit(&gyroConfigMutable()->gyro_soft_notch_hz_1
, LPF_MAX_HZ
);
652 adjustFilterLimit(&gyroConfigMutable()->gyro_soft_notch_cutoff_1
, 0);
653 adjustFilterLimit(&gyroConfigMutable()->gyro_soft_notch_hz_2
, LPF_MAX_HZ
);
654 adjustFilterLimit(&gyroConfigMutable()->gyro_soft_notch_cutoff_2
, 0);
656 // Prevent invalid notch cutoff
657 if (gyroConfig()->gyro_soft_notch_cutoff_1
>= gyroConfig()->gyro_soft_notch_hz_1
) {
658 gyroConfigMutable()->gyro_soft_notch_hz_1
= 0;
660 if (gyroConfig()->gyro_soft_notch_cutoff_2
>= gyroConfig()->gyro_soft_notch_hz_2
) {
661 gyroConfigMutable()->gyro_soft_notch_hz_2
= 0;
664 //Prevent invalid dynamic lowpass filter
665 if (gyroConfig()->gyro_lpf1_dyn_min_hz
> gyroConfig()->gyro_lpf1_dyn_max_hz
) {
666 gyroConfigMutable()->gyro_lpf1_dyn_min_hz
= 0;
670 if (gyro
.sampleRateHz
> 0) {
671 float samplingTime
= 1.0f
/ gyro
.sampleRateHz
;
673 // check for looptime restrictions based on motor protocol. Motor times have safety margin
674 float motorUpdateRestriction
;
676 #if defined(USE_DSHOT) && defined(USE_PID_DENOM_CHECK)
677 /* If bidirectional DSHOT is being used on an F4 or G4 then force DSHOT300. The motor update restrictions then applied
678 * will automatically consider the loop time and adjust pid_process_denom appropriately
680 if (motorConfig()->dev
.useDshotTelemetry
) {
681 if (motorConfig()->dev
.motorPwmProtocol
== PWM_TYPE_DSHOT600
) {
682 motorConfigMutable()->dev
.motorPwmProtocol
= PWM_TYPE_DSHOT300
;
684 if (gyro
.sampleRateHz
> 4000) {
685 pidConfigMutable()->pid_process_denom
= 2;
688 #endif // USE_DSHOT && USE_PID_DENOM_CHECK
689 switch (motorConfig()->dev
.motorPwmProtocol
) {
690 case PWM_TYPE_STANDARD
:
691 motorUpdateRestriction
= 1.0f
/ BRUSHLESS_MOTORS_PWM_RATE
;
693 case PWM_TYPE_ONESHOT125
:
694 motorUpdateRestriction
= 0.0005f
;
696 case PWM_TYPE_ONESHOT42
:
697 motorUpdateRestriction
= 0.0001f
;
700 case PWM_TYPE_DSHOT150
:
701 motorUpdateRestriction
= 0.000250f
;
703 case PWM_TYPE_DSHOT300
:
704 motorUpdateRestriction
= 0.0001f
;
708 motorUpdateRestriction
= 0.00003125f
;
712 if (motorConfig()->dev
.useUnsyncedPwm
) {
713 bool configuredMotorProtocolDshot
= false;
714 checkMotorProtocolEnabled(&motorConfig()->dev
, &configuredMotorProtocolDshot
);
715 // Prevent overriding the max rate of motors
716 if (!configuredMotorProtocolDshot
&& motorConfig()->dev
.motorPwmProtocol
!= PWM_TYPE_STANDARD
) {
717 const uint32_t maxEscRate
= lrintf(1.0f
/ motorUpdateRestriction
);
718 motorConfigMutable()->dev
.motorPwmRate
= MIN(motorConfig()->dev
.motorPwmRate
, maxEscRate
);
721 const float pidLooptime
= samplingTime
* pidConfig()->pid_process_denom
;
722 if (motorConfig()->dev
.useDshotTelemetry
) {
723 motorUpdateRestriction
*= 2;
725 if (pidLooptime
< motorUpdateRestriction
) {
726 uint8_t minPidProcessDenom
= motorUpdateRestriction
/ samplingTime
;
727 if (motorUpdateRestriction
/ samplingTime
> minPidProcessDenom
) {
728 // if any fractional part then round up
729 minPidProcessDenom
++;
731 minPidProcessDenom
= constrain(minPidProcessDenom
, 1, MAX_PID_PROCESS_DENOM
);
732 pidConfigMutable()->pid_process_denom
= MAX(pidConfigMutable()->pid_process_denom
, minPidProcessDenom
);
737 if (systemConfig()->activeRateProfile
>= CONTROL_RATE_PROFILE_COUNT
) {
738 systemConfigMutable()->activeRateProfile
= 0;
740 loadControlRateProfile();
742 if (systemConfig()->pidProfileIndex
>= PID_PROFILE_COUNT
) {
743 systemConfigMutable()->pidProfileIndex
= 0;
749 void validateAndFixBlackBox(void) {
751 if (blackboxConfig()->device
== BLACKBOX_DEVICE_FLASH
) {
752 blackboxConfigMutable()->device
= BLACKBOX_DEVICE_NONE
;
754 #endif // USE_FLASHFS
756 if (blackboxConfig()->device
== BLACKBOX_DEVICE_SDCARD
) {
757 #if defined(USE_SDCARD)
758 if (!sdcardConfig()->mode
)
761 blackboxConfigMutable()->device
= BLACKBOX_DEVICE_NONE
;
765 #endif // USE_BLACKBOX
767 bool readEEPROM(void)
771 // Sanity check, read flash
772 bool success
= loadEEPROM();
776 validateAndFixConfig();
785 void writeUnmodifiedConfigToEEPROM(void)
787 validateAndFixConfig();
790 eepromWriteInProgress
= true;
791 writeConfigToEEPROM();
792 eepromWriteInProgress
= false;
794 configIsDirty
= false;
797 void writeEEPROM(void)
800 rxSpiStop(); // some rx spi protocols use hardware timer, which needs to be stopped before writing to eeprom
802 systemConfigMutable()->configurationState
= CONFIGURATION_STATE_CONFIGURED
;
804 writeUnmodifiedConfigToEEPROM();
807 bool resetEEPROM(void)
811 writeUnmodifiedConfigToEEPROM();
816 void ensureEEPROMStructureIsValid(void)
818 if (isEEPROMStructureValid()) {
824 void saveConfigAndNotify(void)
826 // The write to EEPROM will cause a big delay in the current task, so ignore
827 schedulerIgnoreTaskExecTime();
831 beeperConfirmationBeeps(1);
834 void setConfigDirty(void)
836 configIsDirty
= true;
839 bool isConfigDirty(void)
841 return configIsDirty
;
844 void changePidProfileFromCellCount(uint8_t cellCount
)
846 if (currentPidProfile
->auto_profile_cell_count
== cellCount
|| currentPidProfile
->auto_profile_cell_count
== AUTO_PROFILE_CELL_COUNT_STAY
) {
850 unsigned profileIndex
= (systemConfig()->pidProfileIndex
+ 1) % PID_PROFILE_COUNT
;
851 int matchingProfileIndex
= -1;
852 while (profileIndex
!= systemConfig()->pidProfileIndex
) {
853 if (pidProfiles(profileIndex
)->auto_profile_cell_count
== cellCount
) {
854 matchingProfileIndex
= profileIndex
;
857 } else if (matchingProfileIndex
< 0 && pidProfiles(profileIndex
)->auto_profile_cell_count
== AUTO_PROFILE_CELL_COUNT_STAY
) {
858 matchingProfileIndex
= profileIndex
;
861 profileIndex
= (profileIndex
+ 1) % PID_PROFILE_COUNT
;
864 if (matchingProfileIndex
>= 0) {
865 changePidProfile(matchingProfileIndex
);
869 void changePidProfile(uint8_t pidProfileIndex
)
871 // The config switch will cause a big enough delay in the current task to upset the scheduler
872 schedulerIgnoreTaskExecTime();
874 if (pidProfileIndex
< PID_PROFILE_COUNT
) {
875 systemConfigMutable()->pidProfileIndex
= pidProfileIndex
;
878 pidInit(currentPidProfile
);
883 beeperConfirmationBeeps(pidProfileIndex
+ 1);
886 bool isSystemConfigured(void)
888 return systemConfig()->configurationState
== CONFIGURATION_STATE_CONFIGURED
;
891 void setRebootRequired(void)
893 rebootRequired
= true;
894 setArmingDisabled(ARMING_DISABLED_REBOOT_REQUIRED
);
897 bool getRebootRequired(void)
899 return rebootRequired
;