Removed unused feature 'SOFTSPI'.
[betaflight.git] / src / main / fc / config.c
blobc1b18b3bb7dbe21932ec1e1727c9672587cb6533
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>
25 #include <common/printf.h>
27 #include "platform.h"
29 #include "blackbox/blackbox.h"
31 #include "build/debug.h"
33 #include "cli/cli.h"
35 #include "config/config_eeprom.h"
36 #include "config/feature.h"
38 #include "drivers/dshot_command.h"
39 #include "drivers/motor.h"
40 #include "drivers/system.h"
42 #include "fc/config.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/rpm_filter.h"
55 #include "flight/servos.h"
57 #include "io/beeper.h"
58 #include "io/gps.h"
59 #include "io/ledstrip.h"
60 #include "io/serial.h"
61 #include "io/vtx.h"
63 #include "osd/osd.h"
65 #include "pg/beeper.h"
66 #include "pg/beeper_dev.h"
67 #include "pg/gyrodev.h"
68 #include "pg/pg.h"
69 #include "pg/pg_ids.h"
70 #include "pg/motor.h"
71 #include "pg/rx.h"
72 #include "pg/vtx_table.h"
74 #include "rx/rx.h"
76 #include "scheduler/scheduler.h"
78 #include "sensors/acceleration.h"
79 #include "sensors/battery.h"
80 #include "sensors/compass.h"
81 #include "sensors/gyro.h"
83 #include "common/sensor_alignment.h"
85 static bool configIsDirty; /* someone indicated that the config is modified and it is not yet saved */
87 static bool rebootRequired = false; // set if a config change requires a reboot to take effect
89 pidProfile_t *currentPidProfile;
91 #ifndef RX_SPI_DEFAULT_PROTOCOL
92 #define RX_SPI_DEFAULT_PROTOCOL 0
93 #endif
95 #define DYNAMIC_FILTER_MAX_SUPPORTED_LOOP_TIME HZ_TO_INTERVAL_US(2000)
97 PG_REGISTER_WITH_RESET_TEMPLATE(pilotConfig_t, pilotConfig, PG_PILOT_CONFIG, 1);
99 PG_RESET_TEMPLATE(pilotConfig_t, pilotConfig,
100 .name = { 0 },
101 .displayName = { 0 },
104 PG_REGISTER_WITH_RESET_TEMPLATE(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 2);
106 PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
107 .pidProfileIndex = 0,
108 .activeRateProfile = 0,
109 .debug_mode = DEBUG_MODE,
110 .task_statistics = true,
111 .cpu_overclock = 0,
112 .powerOnArmingGraceTime = 5,
113 .boardIdentifier = TARGET_BOARD_IDENTIFIER,
114 .hseMhz = SYSTEM_HSE_VALUE, // Not used for non-F4 targets
115 .configurationState = CONFIGURATION_STATE_DEFAULTS_BARE,
116 .schedulerOptimizeRate = SCHEDULER_OPTIMIZE_RATE_AUTO,
119 uint8_t getCurrentPidProfileIndex(void)
121 return systemConfig()->pidProfileIndex;
124 static void loadPidProfile(void)
126 currentPidProfile = pidProfilesMutable(systemConfig()->pidProfileIndex);
129 uint8_t getCurrentControlRateProfileIndex(void)
131 return systemConfig()->activeRateProfile;
134 uint16_t getCurrentMinthrottle(void)
136 return motorConfig()->minthrottle;
139 void resetConfig(void)
141 pgResetAll();
143 #if defined(USE_TARGET_CONFIG)
144 targetConfiguration();
145 #endif
148 static void activateConfig(void)
150 schedulerOptimizeRate(systemConfig()->schedulerOptimizeRate == SCHEDULER_OPTIMIZE_RATE_ON || (systemConfig()->schedulerOptimizeRate == SCHEDULER_OPTIMIZE_RATE_AUTO && motorConfig()->dev.useDshotTelemetry));
151 loadPidProfile();
152 loadControlRateProfile();
154 initRcProcessing();
156 activeAdjustmentRangeReset();
158 pidInit(currentPidProfile);
160 rcControlsInit();
162 failsafeReset();
163 #ifdef USE_ACC
164 setAccelerationTrims(&accelerometerConfigMutable()->accZero);
165 accInitFilters();
166 #endif
168 imuConfigure(throttleCorrectionConfig()->throttle_correction_angle, throttleCorrectionConfig()->throttle_correction_value);
170 #if defined(USE_LED_STRIP_STATUS_MODE)
171 reevaluateLedConfig();
172 #endif
175 static void adjustFilterLimit(uint16_t *parm, uint16_t resetValue)
177 if (*parm > FILTER_FREQUENCY_MAX) {
178 *parm = resetValue;
182 static void validateAndFixConfig(void)
184 #if !defined(USE_QUAD_MIXER_ONLY)
185 // Reset unsupported mixer mode to default.
186 // This check will be gone when motor/servo mixers are loaded dynamically
187 // by configurator as a part of configuration procedure.
189 mixerMode_e mixerMode = mixerConfigMutable()->mixerMode;
191 if (!(mixerMode == MIXER_CUSTOM || mixerMode == MIXER_CUSTOM_AIRPLANE || mixerMode == MIXER_CUSTOM_TRI)) {
192 if (mixers[mixerMode].motorCount && mixers[mixerMode].motor == NULL)
193 mixerConfigMutable()->mixerMode = MIXER_CUSTOM;
194 #ifdef USE_SERVOS
195 if (mixers[mixerMode].useServo && servoMixers[mixerMode].servoRuleCount == 0)
196 mixerConfigMutable()->mixerMode = MIXER_CUSTOM_AIRPLANE;
197 #endif
199 #endif
201 if (!isSerialConfigValid(serialConfig())) {
202 pgResetFn_serialConfig(serialConfigMutable());
205 #if defined(USE_GPS)
206 serialPortConfig_t *gpsSerial = findSerialPortConfig(FUNCTION_GPS);
207 if (gpsConfig()->provider == GPS_MSP && gpsSerial) {
208 serialRemovePort(gpsSerial->identifier);
210 #endif
211 if (
212 #if defined(USE_GPS)
213 gpsConfig()->provider != GPS_MSP && !gpsSerial &&
214 #endif
215 true) {
216 featureDisable(FEATURE_GPS);
219 for (unsigned i = 0; i < PID_PROFILE_COUNT; i++) {
220 // Fix filter settings to handle cases where an older configurator was used that
221 // allowed higher cutoff limits from previous firmware versions.
222 adjustFilterLimit(&pidProfilesMutable(i)->dterm_lowpass_hz, FILTER_FREQUENCY_MAX);
223 adjustFilterLimit(&pidProfilesMutable(i)->dterm_lowpass2_hz, FILTER_FREQUENCY_MAX);
224 adjustFilterLimit(&pidProfilesMutable(i)->dterm_notch_hz, FILTER_FREQUENCY_MAX);
225 adjustFilterLimit(&pidProfilesMutable(i)->dterm_notch_cutoff, 0);
227 // Prevent invalid notch cutoff
228 if (pidProfilesMutable(i)->dterm_notch_cutoff >= pidProfilesMutable(i)->dterm_notch_hz) {
229 pidProfilesMutable(i)->dterm_notch_hz = 0;
232 #ifdef USE_DYN_LPF
233 //Prevent invalid dynamic lowpass
234 if (pidProfilesMutable(i)->dyn_lpf_dterm_min_hz > pidProfilesMutable(i)->dyn_lpf_dterm_max_hz) {
235 pidProfilesMutable(i)->dyn_lpf_dterm_min_hz = 0;
237 #endif
239 if (pidProfilesMutable(i)->motor_output_limit > 100 || pidProfilesMutable(i)->motor_output_limit == 0) {
240 pidProfilesMutable(i)->motor_output_limit = 100;
243 if (pidProfilesMutable(i)->auto_profile_cell_count > MAX_AUTO_DETECT_CELL_COUNT || pidProfilesMutable(i)->auto_profile_cell_count < AUTO_PROFILE_CELL_COUNT_CHANGE) {
244 pidProfilesMutable(i)->auto_profile_cell_count = AUTO_PROFILE_CELL_COUNT_STAY;
247 // If the d_min value for any axis is >= the D gain then reset d_min to 0 for consistent Configurator behavior
248 for (unsigned axis = 0; axis <= FD_YAW; axis++) {
249 if (pidProfilesMutable(i)->d_min[axis] >= pidProfilesMutable(i)->pid[axis].D) {
250 pidProfilesMutable(i)->d_min[axis] = 0;
255 if (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_BRUSHED) {
256 featureDisable(FEATURE_3D);
258 if (motorConfig()->mincommand < 1000) {
259 motorConfigMutable()->mincommand = 1000;
263 if ((motorConfig()->dev.motorPwmProtocol == PWM_TYPE_STANDARD) && (motorConfig()->dev.motorPwmRate > BRUSHLESS_MOTORS_PWM_RATE)) {
264 motorConfigMutable()->dev.motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE;
267 validateAndFixGyroConfig();
269 buildAlignmentFromStandardAlignment(&compassConfigMutable()->mag_customAlignment, compassConfig()->mag_alignment);
270 buildAlignmentFromStandardAlignment(&gyroDeviceConfigMutable(0)->customAlignment, gyroDeviceConfig(0)->alignment);
271 #if defined(USE_MULTI_GYRO)
272 buildAlignmentFromStandardAlignment(&gyroDeviceConfigMutable(1)->customAlignment, gyroDeviceConfig(1)->alignment);
273 #endif
275 if (!(featureIsEnabled(FEATURE_RX_PARALLEL_PWM) || featureIsEnabled(FEATURE_RX_PPM) || featureIsEnabled(FEATURE_RX_SERIAL) || featureIsEnabled(FEATURE_RX_MSP) || featureIsEnabled(FEATURE_RX_SPI))) {
276 featureEnable(DEFAULT_RX_FEATURE);
279 if (featureIsEnabled(FEATURE_RX_PPM)) {
280 featureDisable(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_SPI);
283 if (featureIsEnabled(FEATURE_RX_MSP)) {
284 featureDisable(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_SPI);
287 if (featureIsEnabled(FEATURE_RX_SERIAL)) {
288 featureDisable(FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
291 #ifdef USE_RX_SPI
292 if (featureIsEnabled(FEATURE_RX_SPI)) {
293 featureDisable(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_MSP);
295 #endif // USE_RX_SPI
297 if (featureIsEnabled(FEATURE_RX_PARALLEL_PWM)) {
298 featureDisable(FEATURE_RX_SERIAL | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
301 #if defined(USE_ADC)
302 if (featureIsEnabled(FEATURE_RSSI_ADC)) {
303 rxConfigMutable()->rssi_channel = 0;
304 rxConfigMutable()->rssi_src_frame_errors = false;
305 } else
306 #endif
307 if (rxConfigMutable()->rssi_channel
308 #if defined(USE_PWM) || defined(USE_PPM)
309 || featureIsEnabled(FEATURE_RX_PPM) || featureIsEnabled(FEATURE_RX_PARALLEL_PWM)
310 #endif
312 rxConfigMutable()->rssi_src_frame_errors = false;
315 if (!rcSmoothingIsEnabled() || rxConfig()->rcInterpolationChannels == INTERPOLATION_CHANNELS_T) {
316 for (unsigned i = 0; i < PID_PROFILE_COUNT; i++) {
317 pidProfilesMutable(i)->pid[PID_ROLL].F = 0;
318 pidProfilesMutable(i)->pid[PID_PITCH].F = 0;
322 if (!rcSmoothingIsEnabled() ||
323 (rxConfig()->rcInterpolationChannels != INTERPOLATION_CHANNELS_RPY &&
324 rxConfig()->rcInterpolationChannels != INTERPOLATION_CHANNELS_RPYT)) {
326 for (unsigned i = 0; i < PID_PROFILE_COUNT; i++) {
327 pidProfilesMutable(i)->pid[PID_YAW].F = 0;
331 #if defined(USE_THROTTLE_BOOST)
332 if (!rcSmoothingIsEnabled() ||
333 !(rxConfig()->rcInterpolationChannels == INTERPOLATION_CHANNELS_RPYT
334 || rxConfig()->rcInterpolationChannels == INTERPOLATION_CHANNELS_T
335 || rxConfig()->rcInterpolationChannels == INTERPOLATION_CHANNELS_RPT)) {
336 for (unsigned i = 0; i < PID_PROFILE_COUNT; i++) {
337 pidProfilesMutable(i)->throttle_boost = 0;
340 #endif
342 if (
343 featureIsEnabled(FEATURE_3D) || !featureIsEnabled(FEATURE_GPS)
344 #if !defined(USE_GPS) || !defined(USE_GPS_RESCUE)
345 || true
346 #endif
349 #ifdef USE_GPS_RESCUE
350 if (failsafeConfig()->failsafe_procedure == FAILSAFE_PROCEDURE_GPS_RESCUE) {
351 failsafeConfigMutable()->failsafe_procedure = FAILSAFE_PROCEDURE_DROP_IT;
353 #endif
355 if (isModeActivationConditionPresent(BOXGPSRESCUE)) {
356 removeModeActivationCondition(BOXGPSRESCUE);
360 #if defined(USE_ESC_SENSOR)
361 if (!findSerialPortConfig(FUNCTION_ESC_SENSOR)) {
362 featureDisable(FEATURE_ESC_SENSOR);
364 #endif
366 for (int i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
367 const modeActivationCondition_t *mac = modeActivationConditions(i);
369 if (mac->linkedTo) {
370 if (mac->modeId == BOXARM || isModeActivationConditionLinked(mac->linkedTo)) {
371 removeModeActivationCondition(mac->modeId);
376 #if defined(USE_DSHOT_TELEMETRY) && defined(USE_DSHOT_BITBANG)
377 if (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_PROSHOT1000 && motorConfig()->dev.useDshotTelemetry &&
378 motorConfig()->dev.useDshotBitbang == DSHOT_BITBANG_ON) {
379 motorConfigMutable()->dev.useDshotBitbang = DSHOT_BITBANG_AUTO;
381 #endif
383 // clear features that are not supported.
384 // I have kept them all here in one place, some could be moved to sections of code above.
386 #ifndef USE_PPM
387 featureDisable(FEATURE_RX_PPM);
388 #endif
390 #ifndef USE_SERIAL_RX
391 featureDisable(FEATURE_RX_SERIAL);
392 #endif
394 #if !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL2)
395 featureDisable(FEATURE_SOFTSERIAL);
396 #endif
398 #ifndef USE_RANGEFINDER
399 featureDisable(FEATURE_RANGEFINDER);
400 #endif
402 #ifndef USE_TELEMETRY
403 featureDisable(FEATURE_TELEMETRY);
404 #endif
406 #ifndef USE_PWM
407 featureDisable(FEATURE_RX_PARALLEL_PWM);
408 #endif
410 #ifndef USE_RX_MSP
411 featureDisable(FEATURE_RX_MSP);
412 #endif
414 #ifndef USE_LED_STRIP
415 featureDisable(FEATURE_LED_STRIP);
416 #endif
418 #ifndef USE_DASHBOARD
419 featureDisable(FEATURE_DASHBOARD);
420 #endif
422 #ifndef USE_OSD
423 featureDisable(FEATURE_OSD);
424 #endif
426 #ifndef USE_SERVOS
427 featureDisable(FEATURE_SERVO_TILT | FEATURE_CHANNEL_FORWARDING);
428 #endif
430 #ifndef USE_TRANSPONDER
431 featureDisable(FEATURE_TRANSPONDER);
432 #endif
434 #ifndef USE_RX_SPI
435 featureDisable(FEATURE_RX_SPI);
436 #endif
438 #ifndef USE_ESC_SENSOR
439 featureDisable(FEATURE_ESC_SENSOR);
440 #endif
442 #ifndef USE_GYRO_DATA_ANALYSE
443 featureDisable(FEATURE_DYNAMIC_FILTER);
444 #endif
446 #if !defined(USE_ADC)
447 featureDisable(FEATURE_RSSI_ADC);
448 #endif
450 #if defined(USE_BEEPER)
451 #ifdef USE_TIMER
452 if (beeperDevConfig()->frequency && !timerGetByTag(beeperDevConfig()->ioTag)) {
453 beeperDevConfigMutable()->frequency = 0;
455 #endif
457 if (beeperConfig()->beeper_off_flags & ~BEEPER_ALLOWED_MODES) {
458 beeperConfigMutable()->beeper_off_flags = 0;
461 #ifdef USE_DSHOT
462 if (beeperConfig()->dshotBeaconOffFlags & ~DSHOT_BEACON_ALLOWED_MODES) {
463 beeperConfigMutable()->dshotBeaconOffFlags = 0;
466 if (beeperConfig()->dshotBeaconTone < DSHOT_CMD_BEACON1
467 || beeperConfig()->dshotBeaconTone > DSHOT_CMD_BEACON5) {
468 beeperConfigMutable()->dshotBeaconTone = DSHOT_CMD_BEACON1;
470 #endif
471 #endif
473 #if defined(USE_DSHOT)
474 bool usingDshotProtocol;
475 switch (motorConfig()->dev.motorPwmProtocol) {
476 case PWM_TYPE_PROSHOT1000:
477 case PWM_TYPE_DSHOT600:
478 case PWM_TYPE_DSHOT300:
479 case PWM_TYPE_DSHOT150:
480 usingDshotProtocol = true;
481 break;
482 default:
483 usingDshotProtocol = false;
484 break;
487 // If using DSHOT protocol disable unsynched PWM as it's meaningless
488 if (usingDshotProtocol) {
489 motorConfigMutable()->dev.useUnsyncedPwm = false;
492 #if defined(USE_DSHOT_TELEMETRY)
493 if ((!usingDshotProtocol || (motorConfig()->dev.useDshotBitbang == DSHOT_BITBANG_OFF && motorConfig()->dev.useBurstDshot) || systemConfig()->schedulerOptimizeRate == SCHEDULER_OPTIMIZE_RATE_OFF)
494 && motorConfig()->dev.useDshotTelemetry) {
495 motorConfigMutable()->dev.useDshotTelemetry = false;
497 #endif // USE_DSHOT_TELEMETRY
498 #endif // USE_DSHOT
500 #if defined(USE_OSD)
501 for (int i = 0; i < OSD_TIMER_COUNT; i++) {
502 const uint16_t t = osdConfig()->timers[i];
503 if (OSD_TIMER_SRC(t) >= OSD_TIMER_SRC_COUNT ||
504 OSD_TIMER_PRECISION(t) >= OSD_TIMER_PREC_COUNT) {
505 osdConfigMutable()->timers[i] = osdTimerDefault[i];
508 #endif
510 #if defined(USE_VTX_COMMON) && defined(USE_VTX_TABLE)
511 // reset vtx band, channel, power if outside range specified by vtxtable
512 if (vtxSettingsConfig()->channel > vtxTableConfig()->channels) {
513 vtxSettingsConfigMutable()->channel = 0;
514 if (vtxSettingsConfig()->band > 0) {
515 vtxSettingsConfigMutable()->freq = 0; // band/channel determined frequency can't be valid anymore
518 if (vtxSettingsConfig()->band > vtxTableConfig()->bands) {
519 vtxSettingsConfigMutable()->band = 0;
520 vtxSettingsConfigMutable()->freq = 0; // band/channel determined frequency can't be valid anymore
522 if (vtxSettingsConfig()->power > vtxTableConfig()->powerLevels) {
523 vtxSettingsConfigMutable()->power = 0;
525 #endif
527 #if defined(TARGET_VALIDATECONFIG)
528 targetValidateConfiguration();
529 #endif
532 void validateAndFixGyroConfig(void)
534 #ifdef USE_GYRO_DATA_ANALYSE
535 // Disable dynamic filter if gyro loop is less than 2KHz
536 if (gyro.targetLooptime > DYNAMIC_FILTER_MAX_SUPPORTED_LOOP_TIME) {
537 featureDisable(FEATURE_DYNAMIC_FILTER);
539 #endif
541 // Fix gyro filter settings to handle cases where an older configurator was used that
542 // allowed higher cutoff limits from previous firmware versions.
543 adjustFilterLimit(&gyroConfigMutable()->gyro_lowpass_hz, FILTER_FREQUENCY_MAX);
544 adjustFilterLimit(&gyroConfigMutable()->gyro_lowpass2_hz, FILTER_FREQUENCY_MAX);
545 adjustFilterLimit(&gyroConfigMutable()->gyro_soft_notch_hz_1, FILTER_FREQUENCY_MAX);
546 adjustFilterLimit(&gyroConfigMutable()->gyro_soft_notch_cutoff_1, 0);
547 adjustFilterLimit(&gyroConfigMutable()->gyro_soft_notch_hz_2, FILTER_FREQUENCY_MAX);
548 adjustFilterLimit(&gyroConfigMutable()->gyro_soft_notch_cutoff_2, 0);
550 // Prevent invalid notch cutoff
551 if (gyroConfig()->gyro_soft_notch_cutoff_1 >= gyroConfig()->gyro_soft_notch_hz_1) {
552 gyroConfigMutable()->gyro_soft_notch_hz_1 = 0;
554 if (gyroConfig()->gyro_soft_notch_cutoff_2 >= gyroConfig()->gyro_soft_notch_hz_2) {
555 gyroConfigMutable()->gyro_soft_notch_hz_2 = 0;
557 #ifdef USE_DYN_LPF
558 //Prevent invalid dynamic lowpass filter
559 if (gyroConfig()->dyn_lpf_gyro_min_hz > gyroConfig()->dyn_lpf_gyro_max_hz) {
560 gyroConfigMutable()->dyn_lpf_gyro_min_hz = 0;
562 #endif
564 if (gyroConfig()->gyro_hardware_lpf == GYRO_HARDWARE_LPF_1KHZ_SAMPLE) {
565 pidConfigMutable()->pid_process_denom = 1; // When gyro set to 1khz always set pid speed 1:1 to sampling speed
566 gyroConfigMutable()->gyro_sync_denom = 1;
569 #if defined(STM32F1)
570 gyroConfigMutable()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 3);
571 #endif
573 float samplingTime;
574 switch (gyroMpuDetectionResult()->sensor) {
575 case ICM_20649_SPI:
576 samplingTime = 1.0f / 9000.0f;
577 break;
578 case BMI_160_SPI:
579 samplingTime = 0.0003125f;
580 break;
581 default:
582 samplingTime = 0.000125f;
583 break;
585 if (gyroConfig()->gyro_hardware_lpf == GYRO_HARDWARE_LPF_1KHZ_SAMPLE) {
586 switch (gyroMpuDetectionResult()->sensor) {
587 case ICM_20649_SPI:
588 samplingTime = 1.0f / 1100.0f;
589 break;
590 default:
591 samplingTime = 0.001f;
592 break;
597 // check for looptime restrictions based on motor protocol. Motor times have safety margin
598 float motorUpdateRestriction;
599 switch (motorConfig()->dev.motorPwmProtocol) {
600 case PWM_TYPE_STANDARD:
601 motorUpdateRestriction = 1.0f / BRUSHLESS_MOTORS_PWM_RATE;
602 break;
603 case PWM_TYPE_ONESHOT125:
604 motorUpdateRestriction = 0.0005f;
605 break;
606 case PWM_TYPE_ONESHOT42:
607 motorUpdateRestriction = 0.0001f;
608 break;
609 #ifdef USE_DSHOT
610 case PWM_TYPE_DSHOT150:
611 motorUpdateRestriction = 0.000250f;
612 break;
613 case PWM_TYPE_DSHOT300:
614 motorUpdateRestriction = 0.0001f;
615 break;
616 #endif
617 default:
618 motorUpdateRestriction = 0.00003125f;
619 break;
622 if (motorConfig()->dev.useUnsyncedPwm) {
623 // Prevent overriding the max rate of motors
624 if ((motorConfig()->dev.motorPwmProtocol <= PWM_TYPE_BRUSHED) && (motorConfig()->dev.motorPwmProtocol != PWM_TYPE_STANDARD)) {
625 const uint32_t maxEscRate = lrintf(1.0f / motorUpdateRestriction);
626 motorConfigMutable()->dev.motorPwmRate = MIN(motorConfig()->dev.motorPwmRate, maxEscRate);
628 } else {
629 const float pidLooptime = samplingTime * gyroConfig()->gyro_sync_denom * pidConfig()->pid_process_denom;
630 if (pidLooptime < motorUpdateRestriction) {
631 const uint8_t minPidProcessDenom = constrain(motorUpdateRestriction / (samplingTime * gyroConfig()->gyro_sync_denom), 1, MAX_PID_PROCESS_DENOM);
632 pidConfigMutable()->pid_process_denom = MAX(pidConfigMutable()->pid_process_denom, minPidProcessDenom);
636 #ifdef USE_BLACKBOX
637 #ifndef USE_FLASHFS
638 if (blackboxConfig()->device == 1) { // BLACKBOX_DEVICE_FLASH (but not defined)
639 blackboxConfigMutable()->device = BLACKBOX_DEVICE_NONE;
641 #endif // USE_FLASHFS
643 #ifndef USE_SDCARD
644 if (blackboxConfig()->device == 2) { // BLACKBOX_DEVICE_SDCARD (but not defined)
645 blackboxConfigMutable()->device = BLACKBOX_DEVICE_NONE;
647 #endif // USE_SDCARD
648 #endif // USE_BLACKBOX
650 if (systemConfig()->activeRateProfile >= CONTROL_RATE_PROFILE_COUNT) {
651 systemConfigMutable()->activeRateProfile = 0;
653 loadControlRateProfile();
655 if (systemConfig()->pidProfileIndex >= PID_PROFILE_COUNT) {
656 systemConfigMutable()->pidProfileIndex = 0;
658 loadPidProfile();
661 bool readEEPROM(void)
663 suspendRxPwmPpmSignal();
665 // Sanity check, read flash
666 bool success = loadEEPROM();
668 validateAndFixConfig();
670 activateConfig();
672 resumeRxPwmPpmSignal();
674 return success;
677 void writeUnmodifiedConfigToEEPROM(void)
679 validateAndFixConfig();
681 suspendRxPwmPpmSignal();
683 writeConfigToEEPROM();
685 resumeRxPwmPpmSignal();
686 configIsDirty = false;
689 void writeEEPROM(void)
691 systemConfigMutable()->configurationState = CONFIGURATION_STATE_CONFIGURED;
693 writeUnmodifiedConfigToEEPROM();
696 void writeEEPROMWithFeatures(uint32_t features)
698 featureDisableAll();
699 featureEnable(features);
701 writeEEPROM();
704 bool resetEEPROM(bool useCustomDefaults)
706 #if !defined(USE_CUSTOM_DEFAULTS)
707 UNUSED(useCustomDefaults);
708 #else
709 if (useCustomDefaults) {
710 if (!resetConfigToCustomDefaults()) {
711 return false;
713 } else
714 #endif
716 resetConfig();
719 writeUnmodifiedConfigToEEPROM();
721 return true;
724 void ensureEEPROMStructureIsValid(void)
726 if (isEEPROMStructureValid()) {
727 return;
729 resetEEPROM(false);
732 void saveConfigAndNotify(void)
734 writeEEPROM();
735 readEEPROM();
736 beeperConfirmationBeeps(1);
739 void setConfigDirty(void)
741 configIsDirty = true;
744 bool isConfigDirty(void)
746 return configIsDirty;
749 void changePidProfileFromCellCount(uint8_t cellCount)
751 if (currentPidProfile->auto_profile_cell_count == cellCount || currentPidProfile->auto_profile_cell_count == AUTO_PROFILE_CELL_COUNT_STAY) {
752 return;
755 unsigned profileIndex = (systemConfig()->pidProfileIndex + 1) % PID_PROFILE_COUNT;
756 int matchingProfileIndex = -1;
757 while (profileIndex != systemConfig()->pidProfileIndex) {
758 if (pidProfiles(profileIndex)->auto_profile_cell_count == cellCount) {
759 matchingProfileIndex = profileIndex;
761 break;
762 } else if (matchingProfileIndex < 0 && pidProfiles(profileIndex)->auto_profile_cell_count == AUTO_PROFILE_CELL_COUNT_STAY) {
763 matchingProfileIndex = profileIndex;
766 profileIndex = (profileIndex + 1) % PID_PROFILE_COUNT;
769 if (matchingProfileIndex >= 0) {
770 changePidProfile(matchingProfileIndex);
774 void changePidProfile(uint8_t pidProfileIndex)
776 if (pidProfileIndex < PID_PROFILE_COUNT) {
777 systemConfigMutable()->pidProfileIndex = pidProfileIndex;
778 loadPidProfile();
780 pidInit(currentPidProfile);
781 initEscEndpoints();
784 beeperConfirmationBeeps(pidProfileIndex + 1);
787 bool isSystemConfigured(void)
789 return systemConfig()->configurationState == CONFIGURATION_STATE_CONFIGURED;
792 void setRebootRequired(void)
794 rebootRequired = true;
795 setArmingDisabled(ARMING_DISABLED_REBOOT_REQUIRED);
798 bool getRebootRequired(void)
800 return rebootRequired;