New SPI API supporting DMA
[betaflight.git] / src / main / config / config.c
blobe4f66f028e47e29de01bf0e73bdddebfcdb00e25
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"
58 #include "io/beeper.h"
59 #include "io/gps.h"
60 #include "io/ledstrip.h"
61 #include "io/serial.h"
62 #include "io/vtx.h"
64 #include "msp/msp_box.h"
66 #include "osd/osd.h"
68 #include "pg/adc.h"
69 #include "pg/beeper.h"
70 #include "pg/beeper_dev.h"
71 #include "pg/displayport_profiles.h"
72 #include "pg/gyrodev.h"
73 #include "pg/motor.h"
74 #include "pg/pg.h"
75 #include "pg/pg_ids.h"
76 #include "pg/rx.h"
77 #include "pg/rx_spi.h"
78 #include "pg/sdcard.h"
79 #include "pg/vtx_table.h"
81 #include "rx/rx.h"
82 #include "rx/rx_spi.h"
84 #include "scheduler/scheduler.h"
86 #include "sensors/acceleration.h"
87 #include "sensors/battery.h"
88 #include "sensors/compass.h"
89 #include "sensors/gyro.h"
91 #include "config.h"
93 #include "drivers/dshot.h"
95 static bool configIsDirty; /* someone indicated that the config is modified and it is not yet saved */
97 static bool rebootRequired = false; // set if a config change requires a reboot to take effect
99 pidProfile_t *currentPidProfile;
101 #ifndef RX_SPI_DEFAULT_PROTOCOL
102 #define RX_SPI_DEFAULT_PROTOCOL 0
103 #endif
105 #define DYNAMIC_FILTER_MAX_SUPPORTED_LOOP_TIME HZ_TO_INTERVAL_US(2000)
107 PG_REGISTER_WITH_RESET_TEMPLATE(pilotConfig_t, pilotConfig, PG_PILOT_CONFIG, 1);
109 PG_RESET_TEMPLATE(pilotConfig_t, pilotConfig,
110 .name = { 0 },
111 .displayName = { 0 },
114 PG_REGISTER_WITH_RESET_TEMPLATE(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 2);
116 PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
117 .pidProfileIndex = 0,
118 .activeRateProfile = 0,
119 .debug_mode = DEBUG_MODE,
120 .task_statistics = true,
121 .rateProfile6PosSwitch = false,
122 .cpu_overclock = DEFAULT_CPU_OVERCLOCK,
123 .powerOnArmingGraceTime = 5,
124 .boardIdentifier = TARGET_BOARD_IDENTIFIER,
125 .hseMhz = SYSTEM_HSE_VALUE, // Only used for F4 and G4 targets
126 .configurationState = CONFIGURATION_STATE_DEFAULTS_BARE,
127 .schedulerOptimizeRate = SCHEDULER_OPTIMIZE_RATE_AUTO,
128 .enableStickArming = false,
131 uint8_t getCurrentPidProfileIndex(void)
133 return systemConfig()->pidProfileIndex;
136 static void loadPidProfile(void)
138 currentPidProfile = pidProfilesMutable(systemConfig()->pidProfileIndex);
141 uint8_t getCurrentControlRateProfileIndex(void)
143 return systemConfig()->activeRateProfile;
146 uint16_t getCurrentMinthrottle(void)
148 return motorConfig()->minthrottle;
151 void resetConfig(void)
153 pgResetAll();
155 #if defined(USE_TARGET_CONFIG)
156 targetConfiguration();
157 #endif
160 static void activateConfig(void)
162 schedulerOptimizeRate(systemConfig()->schedulerOptimizeRate == SCHEDULER_OPTIMIZE_RATE_ON || (systemConfig()->schedulerOptimizeRate == SCHEDULER_OPTIMIZE_RATE_AUTO && motorConfig()->dev.useDshotTelemetry));
163 loadPidProfile();
164 loadControlRateProfile();
166 initRcProcessing();
168 activeAdjustmentRangeReset();
170 pidInit(currentPidProfile);
172 rcControlsInit();
174 failsafeReset();
175 #ifdef USE_ACC
176 setAccelerationTrims(&accelerometerConfigMutable()->accZero);
177 accInitFilters();
178 #endif
180 imuConfigure(throttleCorrectionConfig()->throttle_correction_angle, throttleCorrectionConfig()->throttle_correction_value);
182 #if defined(USE_LED_STRIP_STATUS_MODE)
183 reevaluateLedConfig();
184 #endif
186 initActiveBoxIds();
189 static void adjustFilterLimit(uint16_t *parm, uint16_t resetValue)
191 if (*parm > FILTER_FREQUENCY_MAX) {
192 *parm = resetValue;
196 static void validateAndFixRatesSettings(void)
198 for (unsigned profileIndex = 0; profileIndex < CONTROL_RATE_PROFILE_COUNT; profileIndex++) {
199 const ratesType_e ratesType = controlRateProfilesMutable(profileIndex)->rates_type;
200 for (unsigned axis = FD_ROLL; axis <= FD_YAW; axis++) {
201 controlRateProfilesMutable(profileIndex)->rcRates[axis] = constrain(controlRateProfilesMutable(profileIndex)->rcRates[axis], 0, ratesSettingLimits[ratesType].rc_rate_limit);
202 controlRateProfilesMutable(profileIndex)->rates[axis] = constrain(controlRateProfilesMutable(profileIndex)->rates[axis], 0, ratesSettingLimits[ratesType].srate_limit);
203 controlRateProfilesMutable(profileIndex)->rcExpo[axis] = constrain(controlRateProfilesMutable(profileIndex)->rcExpo[axis], 0, ratesSettingLimits[ratesType].expo_limit);
208 static void validateAndFixConfig(void)
210 #if !defined(USE_QUAD_MIXER_ONLY)
211 // Reset unsupported mixer mode to default.
212 // This check will be gone when motor/servo mixers are loaded dynamically
213 // by configurator as a part of configuration procedure.
215 mixerMode_e mixerMode = mixerConfigMutable()->mixerMode;
217 if (!(mixerMode == MIXER_CUSTOM || mixerMode == MIXER_CUSTOM_AIRPLANE || mixerMode == MIXER_CUSTOM_TRI)) {
218 if (mixers[mixerMode].motorCount && mixers[mixerMode].motor == NULL)
219 mixerConfigMutable()->mixerMode = MIXER_CUSTOM;
220 #ifdef USE_SERVOS
221 if (mixers[mixerMode].useServo && servoMixers[mixerMode].servoRuleCount == 0)
222 mixerConfigMutable()->mixerMode = MIXER_CUSTOM_AIRPLANE;
223 #endif
225 #endif
227 if (!isSerialConfigValid(serialConfig())) {
228 pgResetFn_serialConfig(serialConfigMutable());
231 #if defined(USE_GPS)
232 const serialPortConfig_t *gpsSerial = findSerialPortConfig(FUNCTION_GPS);
233 if (gpsConfig()->provider == GPS_MSP && gpsSerial) {
234 serialRemovePort(gpsSerial->identifier);
236 #endif
237 if (
238 #if defined(USE_GPS)
239 gpsConfig()->provider != GPS_MSP && !gpsSerial &&
240 #endif
241 true) {
242 featureDisableImmediate(FEATURE_GPS);
245 for (unsigned i = 0; i < PID_PROFILE_COUNT; i++) {
246 // Fix filter settings to handle cases where an older configurator was used that
247 // allowed higher cutoff limits from previous firmware versions.
248 adjustFilterLimit(&pidProfilesMutable(i)->dterm_lowpass_hz, FILTER_FREQUENCY_MAX);
249 adjustFilterLimit(&pidProfilesMutable(i)->dterm_lowpass2_hz, FILTER_FREQUENCY_MAX);
250 adjustFilterLimit(&pidProfilesMutable(i)->dterm_notch_hz, FILTER_FREQUENCY_MAX);
251 adjustFilterLimit(&pidProfilesMutable(i)->dterm_notch_cutoff, 0);
253 // Prevent invalid notch cutoff
254 if (pidProfilesMutable(i)->dterm_notch_cutoff >= pidProfilesMutable(i)->dterm_notch_hz) {
255 pidProfilesMutable(i)->dterm_notch_hz = 0;
258 #ifdef USE_DYN_LPF
259 //Prevent invalid dynamic lowpass
260 if (pidProfilesMutable(i)->dyn_lpf_dterm_min_hz > pidProfilesMutable(i)->dyn_lpf_dterm_max_hz) {
261 pidProfilesMutable(i)->dyn_lpf_dterm_min_hz = 0;
263 #endif
265 if (pidProfilesMutable(i)->motor_output_limit > 100 || pidProfilesMutable(i)->motor_output_limit == 0) {
266 pidProfilesMutable(i)->motor_output_limit = 100;
269 if (pidProfilesMutable(i)->auto_profile_cell_count > MAX_AUTO_DETECT_CELL_COUNT || pidProfilesMutable(i)->auto_profile_cell_count < AUTO_PROFILE_CELL_COUNT_CHANGE) {
270 pidProfilesMutable(i)->auto_profile_cell_count = AUTO_PROFILE_CELL_COUNT_STAY;
273 // If the d_min value for any axis is >= the D gain then reset d_min to 0 for consistent Configurator behavior
274 for (unsigned axis = 0; axis <= FD_YAW; axis++) {
275 if (pidProfilesMutable(i)->d_min[axis] >= pidProfilesMutable(i)->pid[axis].D) {
276 pidProfilesMutable(i)->d_min[axis] = 0;
280 #if defined(USE_BATTERY_VOLTAGE_SAG_COMPENSATION)
281 if (batteryConfig()->voltageMeterSource != VOLTAGE_METER_ADC) {
282 pidProfilesMutable(i)->vbat_sag_compensation = 0;
284 #endif
287 if (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_BRUSHED) {
288 featureDisableImmediate(FEATURE_3D);
290 if (motorConfig()->mincommand < 1000) {
291 motorConfigMutable()->mincommand = 1000;
295 if ((motorConfig()->dev.motorPwmProtocol == PWM_TYPE_STANDARD) && (motorConfig()->dev.motorPwmRate > BRUSHLESS_MOTORS_PWM_RATE)) {
296 motorConfigMutable()->dev.motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE;
299 validateAndFixGyroConfig();
301 #if defined(USE_MAG)
302 buildAlignmentFromStandardAlignment(&compassConfigMutable()->mag_customAlignment, compassConfig()->mag_alignment);
303 #endif
304 buildAlignmentFromStandardAlignment(&gyroDeviceConfigMutable(0)->customAlignment, gyroDeviceConfig(0)->alignment);
305 #if defined(USE_MULTI_GYRO)
306 buildAlignmentFromStandardAlignment(&gyroDeviceConfigMutable(1)->customAlignment, gyroDeviceConfig(1)->alignment);
307 #endif
309 #ifdef USE_ACC
310 if (accelerometerConfig()->accZero.values.roll != 0 ||
311 accelerometerConfig()->accZero.values.pitch != 0 ||
312 accelerometerConfig()->accZero.values.yaw != 0) {
313 accelerometerConfigMutable()->accZero.values.calibrationCompleted = 1;
315 #endif // USE_ACC
317 if (!(featureIsConfigured(FEATURE_RX_PARALLEL_PWM) || featureIsConfigured(FEATURE_RX_PPM) || featureIsConfigured(FEATURE_RX_SERIAL) || featureIsConfigured(FEATURE_RX_MSP) || featureIsConfigured(FEATURE_RX_SPI))) {
318 featureEnableImmediate(DEFAULT_RX_FEATURE);
321 if (featureIsConfigured(FEATURE_RX_PPM)) {
322 featureDisableImmediate(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_SPI);
325 if (featureIsConfigured(FEATURE_RX_MSP)) {
326 featureDisableImmediate(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_SPI);
329 if (featureIsConfigured(FEATURE_RX_SERIAL)) {
330 featureDisableImmediate(FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
333 #ifdef USE_RX_SPI
334 if (featureIsConfigured(FEATURE_RX_SPI)) {
335 featureDisableImmediate(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_MSP);
337 #endif // USE_RX_SPI
339 if (featureIsConfigured(FEATURE_RX_PARALLEL_PWM)) {
340 featureDisableImmediate(FEATURE_RX_SERIAL | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
343 #if defined(USE_ADC)
344 if (featureIsConfigured(FEATURE_RSSI_ADC)) {
345 rxConfigMutable()->rssi_channel = 0;
346 rxConfigMutable()->rssi_src_frame_errors = false;
347 } else
348 #endif
349 if (rxConfigMutable()->rssi_channel
350 #if defined(USE_PWM) || defined(USE_PPM)
351 || featureIsConfigured(FEATURE_RX_PPM) || featureIsConfigured(FEATURE_RX_PARALLEL_PWM)
352 #endif
354 rxConfigMutable()->rssi_src_frame_errors = false;
357 if (
358 featureIsConfigured(FEATURE_3D) || !featureIsConfigured(FEATURE_GPS) || mixerModeIsFixedWing(mixerConfig()->mixerMode)
359 #if !defined(USE_GPS) || !defined(USE_GPS_RESCUE)
360 || true
361 #endif
364 #ifdef USE_GPS_RESCUE
365 if (failsafeConfig()->failsafe_procedure == FAILSAFE_PROCEDURE_GPS_RESCUE) {
366 failsafeConfigMutable()->failsafe_procedure = FAILSAFE_PROCEDURE_DROP_IT;
368 #endif
370 if (isModeActivationConditionPresent(BOXGPSRESCUE)) {
371 removeModeActivationCondition(BOXGPSRESCUE);
375 #if defined(USE_ESC_SENSOR)
376 if (!findSerialPortConfig(FUNCTION_ESC_SENSOR)) {
377 featureDisableImmediate(FEATURE_ESC_SENSOR);
379 #endif
381 for (int i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
382 const modeActivationCondition_t *mac = modeActivationConditions(i);
384 if (mac->linkedTo) {
385 if (mac->modeId == BOXARM || isModeActivationConditionLinked(mac->linkedTo)) {
386 removeModeActivationCondition(mac->modeId);
391 #if defined(USE_DSHOT_TELEMETRY) && defined(USE_DSHOT_BITBANG)
392 if (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_PROSHOT1000 && motorConfig()->dev.useDshotTelemetry &&
393 motorConfig()->dev.useDshotBitbang == DSHOT_BITBANG_ON) {
394 motorConfigMutable()->dev.useDshotBitbang = DSHOT_BITBANG_AUTO;
396 #endif
398 #ifdef USE_ADC
399 adcConfigMutable()->vbat.enabled = (batteryConfig()->voltageMeterSource == VOLTAGE_METER_ADC);
400 adcConfigMutable()->current.enabled = (batteryConfig()->currentMeterSource == CURRENT_METER_ADC);
402 // The FrSky D SPI RX sends RSSI_ADC_PIN (if configured) as A2
403 adcConfigMutable()->rssi.enabled = featureIsEnabled(FEATURE_RSSI_ADC);
404 #ifdef USE_RX_SPI
405 adcConfigMutable()->rssi.enabled |= (featureIsEnabled(FEATURE_RX_SPI) && rxSpiConfig()->rx_spi_protocol == RX_SPI_FRSKY_D);
406 #endif
407 #endif // USE_ADC
410 // clear features that are not supported.
411 // I have kept them all here in one place, some could be moved to sections of code above.
413 #ifndef USE_PPM
414 featureDisableImmediate(FEATURE_RX_PPM);
415 #endif
417 #ifndef USE_SERIAL_RX
418 featureDisableImmediate(FEATURE_RX_SERIAL);
419 #endif
421 #if !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL2)
422 featureDisableImmediate(FEATURE_SOFTSERIAL);
423 #endif
425 #ifndef USE_RANGEFINDER
426 featureDisableImmediate(FEATURE_RANGEFINDER);
427 #endif
429 #ifndef USE_TELEMETRY
430 featureDisableImmediate(FEATURE_TELEMETRY);
431 #endif
433 #ifndef USE_PWM
434 featureDisableImmediate(FEATURE_RX_PARALLEL_PWM);
435 #endif
437 #ifndef USE_RX_MSP
438 featureDisableImmediate(FEATURE_RX_MSP);
439 #endif
441 #ifndef USE_LED_STRIP
442 featureDisableImmediate(FEATURE_LED_STRIP);
443 #endif
445 #ifndef USE_DASHBOARD
446 featureDisableImmediate(FEATURE_DASHBOARD);
447 #endif
449 #ifndef USE_OSD
450 featureDisableImmediate(FEATURE_OSD);
451 #endif
453 #ifndef USE_SERVOS
454 featureDisableImmediate(FEATURE_SERVO_TILT | FEATURE_CHANNEL_FORWARDING);
455 #endif
457 #ifndef USE_TRANSPONDER
458 featureDisableImmediate(FEATURE_TRANSPONDER);
459 #endif
461 #ifndef USE_RX_SPI
462 featureDisableImmediate(FEATURE_RX_SPI);
463 #endif
465 #ifndef USE_ESC_SENSOR
466 featureDisableImmediate(FEATURE_ESC_SENSOR);
467 #endif
469 #ifndef USE_GYRO_DATA_ANALYSE
470 featureDisableImmediate(FEATURE_DYNAMIC_FILTER);
471 #endif
473 #if !defined(USE_ADC)
474 featureDisableImmediate(FEATURE_RSSI_ADC);
475 #endif
477 #if defined(USE_BEEPER)
478 #ifdef USE_TIMER
479 if (beeperDevConfig()->frequency && !timerGetByTag(beeperDevConfig()->ioTag)) {
480 beeperDevConfigMutable()->frequency = 0;
482 #endif
484 if (beeperConfig()->beeper_off_flags & ~BEEPER_ALLOWED_MODES) {
485 beeperConfigMutable()->beeper_off_flags = 0;
488 #ifdef USE_DSHOT
489 if (beeperConfig()->dshotBeaconOffFlags & ~DSHOT_BEACON_ALLOWED_MODES) {
490 beeperConfigMutable()->dshotBeaconOffFlags = 0;
493 if (beeperConfig()->dshotBeaconTone < DSHOT_CMD_BEACON1
494 || beeperConfig()->dshotBeaconTone > DSHOT_CMD_BEACON5) {
495 beeperConfigMutable()->dshotBeaconTone = DSHOT_CMD_BEACON1;
497 #endif
498 #endif
500 bool configuredMotorProtocolDshot = false;
501 checkMotorProtocolEnabled(&motorConfig()->dev, &configuredMotorProtocolDshot);
502 #if defined(USE_DSHOT)
503 // If using DSHOT protocol disable unsynched PWM as it's meaningless
504 if (configuredMotorProtocolDshot) {
505 motorConfigMutable()->dev.useUnsyncedPwm = false;
508 #if defined(USE_DSHOT_TELEMETRY)
509 if ((!configuredMotorProtocolDshot || (motorConfig()->dev.useDshotBitbang == DSHOT_BITBANG_OFF && motorConfig()->dev.useBurstDshot == DSHOT_DMAR_ON) || systemConfig()->schedulerOptimizeRate == SCHEDULER_OPTIMIZE_RATE_OFF)
510 && motorConfig()->dev.useDshotTelemetry) {
511 motorConfigMutable()->dev.useDshotTelemetry = false;
514 #if defined(USE_DYN_IDLE)
515 if (!isRpmFilterEnabled()) {
516 for (unsigned i = 0; i < PID_PROFILE_COUNT; i++) {
517 pidProfilesMutable(i)->dyn_idle_min_rpm = 0;
520 #endif // USE_DYN_IDLE
521 #endif // USE_DSHOT_TELEMETRY
522 #endif // USE_DSHOT
524 #if defined(USE_OSD)
525 for (int i = 0; i < OSD_TIMER_COUNT; i++) {
526 const uint16_t t = osdConfig()->timers[i];
527 if (OSD_TIMER_SRC(t) >= OSD_TIMER_SRC_COUNT ||
528 OSD_TIMER_PRECISION(t) >= OSD_TIMER_PREC_COUNT) {
529 osdConfigMutable()->timers[i] = osdTimerDefault[i];
532 #endif
534 #if defined(USE_VTX_COMMON) && defined(USE_VTX_TABLE)
535 // reset vtx band, channel, power if outside range specified by vtxtable
536 if (vtxSettingsConfig()->channel > vtxTableConfig()->channels) {
537 vtxSettingsConfigMutable()->channel = 0;
538 if (vtxSettingsConfig()->band > 0) {
539 vtxSettingsConfigMutable()->freq = 0; // band/channel determined frequency can't be valid anymore
542 if (vtxSettingsConfig()->band > vtxTableConfig()->bands) {
543 vtxSettingsConfigMutable()->band = 0;
544 vtxSettingsConfigMutable()->freq = 0; // band/channel determined frequency can't be valid anymore
546 if (vtxSettingsConfig()->power > vtxTableConfig()->powerLevels) {
547 vtxSettingsConfigMutable()->power = 0;
549 #endif
551 validateAndFixRatesSettings(); // constrain the various rates settings to limits imposed by the rates type
553 #if defined(USE_RX_MSP_OVERRIDE)
554 if (!rxConfig()->msp_override_channels_mask) {
555 removeModeActivationCondition(BOXMSPOVERRIDE);
558 for (int i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
559 const modeActivationCondition_t *mac = modeActivationConditions(i);
560 if (mac->modeId == BOXMSPOVERRIDE && ((1 << (mac->auxChannelIndex) & (rxConfig()->msp_override_channels_mask)))) {
561 rxConfigMutable()->msp_override_channels_mask &= ~(1 << (mac->auxChannelIndex + NON_AUX_CHANNEL_COUNT));
564 #endif
566 validateAndfixMotorOutputReordering(motorConfigMutable()->dev.motorOutputReordering, MAX_SUPPORTED_MOTORS);
568 // validate that the minimum battery cell voltage is less than the maximum cell voltage
569 // reset to defaults if not
570 if (batteryConfig()->vbatmincellvoltage >= batteryConfig()->vbatmaxcellvoltage) {
571 batteryConfigMutable()->vbatmincellvoltage = VBAT_CELL_VOLTAGE_DEFAULT_MIN;
572 batteryConfigMutable()->vbatmaxcellvoltage = VBAT_CELL_VOLTAGE_DEFAULT_MAX;
575 #ifdef USE_MSP_DISPLAYPORT
576 // validate that displayport_msp_serial is referencing a valid UART that actually has MSP enabled
577 if (displayPortProfileMsp()->displayPortSerial != SERIAL_PORT_NONE) {
578 const serialPortConfig_t *portConfig = serialFindPortConfiguration(displayPortProfileMsp()->displayPortSerial);
579 if (!portConfig || !(portConfig->functionMask & FUNCTION_MSP)
580 #ifndef USE_MSP_PUSH_OVER_VCP
581 || (portConfig->identifier == SERIAL_PORT_USB_VCP)
582 #endif
584 displayPortProfileMspMutable()->displayPortSerial = SERIAL_PORT_NONE;
587 #endif
589 #if defined(TARGET_VALIDATECONFIG)
590 // This should be done at the end of the validation
591 targetValidateConfiguration();
592 #endif
595 void validateAndFixGyroConfig(void)
597 // Fix gyro filter settings to handle cases where an older configurator was used that
598 // allowed higher cutoff limits from previous firmware versions.
599 adjustFilterLimit(&gyroConfigMutable()->gyro_lowpass_hz, FILTER_FREQUENCY_MAX);
600 adjustFilterLimit(&gyroConfigMutable()->gyro_lowpass2_hz, FILTER_FREQUENCY_MAX);
601 adjustFilterLimit(&gyroConfigMutable()->gyro_soft_notch_hz_1, FILTER_FREQUENCY_MAX);
602 adjustFilterLimit(&gyroConfigMutable()->gyro_soft_notch_cutoff_1, 0);
603 adjustFilterLimit(&gyroConfigMutable()->gyro_soft_notch_hz_2, FILTER_FREQUENCY_MAX);
604 adjustFilterLimit(&gyroConfigMutable()->gyro_soft_notch_cutoff_2, 0);
606 // Prevent invalid notch cutoff
607 if (gyroConfig()->gyro_soft_notch_cutoff_1 >= gyroConfig()->gyro_soft_notch_hz_1) {
608 gyroConfigMutable()->gyro_soft_notch_hz_1 = 0;
610 if (gyroConfig()->gyro_soft_notch_cutoff_2 >= gyroConfig()->gyro_soft_notch_hz_2) {
611 gyroConfigMutable()->gyro_soft_notch_hz_2 = 0;
613 #ifdef USE_DYN_LPF
614 //Prevent invalid dynamic lowpass filter
615 if (gyroConfig()->dyn_lpf_gyro_min_hz > gyroConfig()->dyn_lpf_gyro_max_hz) {
616 gyroConfigMutable()->dyn_lpf_gyro_min_hz = 0;
618 #endif
620 if (gyro.sampleRateHz > 0) {
621 float samplingTime = 1.0f / gyro.sampleRateHz;
623 // check for looptime restrictions based on motor protocol. Motor times have safety margin
624 float motorUpdateRestriction;
625 switch (motorConfig()->dev.motorPwmProtocol) {
626 case PWM_TYPE_STANDARD:
627 motorUpdateRestriction = 1.0f / BRUSHLESS_MOTORS_PWM_RATE;
628 break;
629 case PWM_TYPE_ONESHOT125:
630 motorUpdateRestriction = 0.0005f;
631 break;
632 case PWM_TYPE_ONESHOT42:
633 motorUpdateRestriction = 0.0001f;
634 break;
635 #ifdef USE_DSHOT
636 case PWM_TYPE_DSHOT150:
637 motorUpdateRestriction = 0.000250f;
638 break;
639 case PWM_TYPE_DSHOT300:
640 motorUpdateRestriction = 0.0001f;
641 break;
642 #endif
643 default:
644 motorUpdateRestriction = 0.00003125f;
645 break;
648 if (motorConfig()->dev.useUnsyncedPwm) {
649 bool configuredMotorProtocolDshot = false;
650 checkMotorProtocolEnabled(&motorConfig()->dev, &configuredMotorProtocolDshot);
651 // Prevent overriding the max rate of motors
652 if (!configuredMotorProtocolDshot && motorConfig()->dev.motorPwmProtocol != PWM_TYPE_STANDARD) {
653 const uint32_t maxEscRate = lrintf(1.0f / motorUpdateRestriction);
654 motorConfigMutable()->dev.motorPwmRate = MIN(motorConfig()->dev.motorPwmRate, maxEscRate);
656 } else {
657 const float pidLooptime = samplingTime * pidConfig()->pid_process_denom;
658 if (motorConfig()->dev.useDshotTelemetry) {
659 motorUpdateRestriction *= 2;
661 if (pidLooptime < motorUpdateRestriction) {
662 uint8_t minPidProcessDenom = motorUpdateRestriction / samplingTime;
663 if (motorUpdateRestriction / samplingTime > minPidProcessDenom) {
664 // if any fractional part then round up
665 minPidProcessDenom++;
667 minPidProcessDenom = constrain(minPidProcessDenom, 1, MAX_PID_PROCESS_DENOM);
668 pidConfigMutable()->pid_process_denom = MAX(pidConfigMutable()->pid_process_denom, minPidProcessDenom);
673 #ifdef USE_GYRO_DATA_ANALYSE
674 // Disable dynamic filter if gyro loop is less than 2KHz
675 const uint32_t configuredLooptime = (gyro.sampleRateHz > 0) ? (pidConfig()->pid_process_denom * 1e6 / gyro.sampleRateHz) : 0;
676 if (configuredLooptime > DYNAMIC_FILTER_MAX_SUPPORTED_LOOP_TIME) {
677 featureDisableImmediate(FEATURE_DYNAMIC_FILTER);
679 #endif
681 #ifdef USE_BLACKBOX
682 #ifndef USE_FLASHFS
683 if (blackboxConfig()->device == BLACKBOX_DEVICE_FLASH) {
684 blackboxConfigMutable()->device = BLACKBOX_DEVICE_NONE;
686 #endif // USE_FLASHFS
688 if (blackboxConfig()->device == BLACKBOX_DEVICE_SDCARD) {
689 #if defined(USE_SDCARD)
690 if (!sdcardConfig()->mode)
691 #endif
693 blackboxConfigMutable()->device = BLACKBOX_DEVICE_NONE;
696 #endif // USE_BLACKBOX
698 if (systemConfig()->activeRateProfile >= CONTROL_RATE_PROFILE_COUNT) {
699 systemConfigMutable()->activeRateProfile = 0;
701 loadControlRateProfile();
703 if (systemConfig()->pidProfileIndex >= PID_PROFILE_COUNT) {
704 systemConfigMutable()->pidProfileIndex = 0;
706 loadPidProfile();
709 bool readEEPROM(void)
711 suspendRxPwmPpmSignal();
713 // Sanity check, read flash
714 bool success = loadEEPROM();
716 featureInit();
718 validateAndFixConfig();
720 activateConfig();
722 resumeRxPwmPpmSignal();
724 return success;
727 void writeUnmodifiedConfigToEEPROM(void)
729 validateAndFixConfig();
731 suspendRxPwmPpmSignal();
733 writeConfigToEEPROM();
735 resumeRxPwmPpmSignal();
736 configIsDirty = false;
739 void writeEEPROM(void)
741 systemConfigMutable()->configurationState = CONFIGURATION_STATE_CONFIGURED;
743 writeUnmodifiedConfigToEEPROM();
746 bool resetEEPROM(bool useCustomDefaults)
748 #if !defined(USE_CUSTOM_DEFAULTS)
749 UNUSED(useCustomDefaults);
750 #else
751 if (useCustomDefaults) {
752 if (!resetConfigToCustomDefaults()) {
753 return false;
755 } else
756 #endif
758 resetConfig();
761 writeUnmodifiedConfigToEEPROM();
763 return true;
766 void ensureEEPROMStructureIsValid(void)
768 if (isEEPROMStructureValid()) {
769 return;
771 resetEEPROM(false);
774 void saveConfigAndNotify(void)
776 writeEEPROM();
777 readEEPROM();
778 beeperConfirmationBeeps(1);
781 void setConfigDirty(void)
783 configIsDirty = true;
786 bool isConfigDirty(void)
788 return configIsDirty;
791 void changePidProfileFromCellCount(uint8_t cellCount)
793 if (currentPidProfile->auto_profile_cell_count == cellCount || currentPidProfile->auto_profile_cell_count == AUTO_PROFILE_CELL_COUNT_STAY) {
794 return;
797 unsigned profileIndex = (systemConfig()->pidProfileIndex + 1) % PID_PROFILE_COUNT;
798 int matchingProfileIndex = -1;
799 while (profileIndex != systemConfig()->pidProfileIndex) {
800 if (pidProfiles(profileIndex)->auto_profile_cell_count == cellCount) {
801 matchingProfileIndex = profileIndex;
803 break;
804 } else if (matchingProfileIndex < 0 && pidProfiles(profileIndex)->auto_profile_cell_count == AUTO_PROFILE_CELL_COUNT_STAY) {
805 matchingProfileIndex = profileIndex;
808 profileIndex = (profileIndex + 1) % PID_PROFILE_COUNT;
811 if (matchingProfileIndex >= 0) {
812 changePidProfile(matchingProfileIndex);
816 void changePidProfile(uint8_t pidProfileIndex)
818 if (pidProfileIndex < PID_PROFILE_COUNT) {
819 systemConfigMutable()->pidProfileIndex = pidProfileIndex;
820 loadPidProfile();
822 pidInit(currentPidProfile);
823 initEscEndpoints();
824 mixerInitProfile();
827 beeperConfirmationBeeps(pidProfileIndex + 1);
830 bool isSystemConfigured(void)
832 return systemConfig()->configurationState == CONFIGURATION_STATE_CONFIGURED;
835 void setRebootRequired(void)
837 rebootRequired = true;
838 setArmingDisabled(ARMING_DISABLED_REBOOT_REQUIRED);
841 bool getRebootRequired(void)
843 return rebootRequired;