Added battery cell count based automatic PID profile switching.
[betaflight.git] / src / main / fc / config.c
blobb886c1e9495a3d0af8326c3b4d2b72eee7f93228
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 "config/config_eeprom.h"
33 #include "config/feature.h"
35 #include "drivers/system.h"
37 #include "fc/config.h"
38 #include "fc/controlrate_profile.h"
39 #include "fc/core.h"
40 #include "fc/rc.h"
41 #include "fc/rc_adjustments.h"
42 #include "fc/rc_controls.h"
44 #include "flight/failsafe.h"
45 #include "flight/imu.h"
46 #include "flight/mixer.h"
47 #include "flight/pid.h"
48 #include "flight/servos.h"
50 #include "io/beeper.h"
51 #include "io/ledstrip.h"
52 #include "io/serial.h"
53 #include "io/gps.h"
55 #include "pg/beeper.h"
56 #include "pg/beeper_dev.h"
57 #include "pg/rx.h"
58 #include "pg/pg.h"
59 #include "pg/pg_ids.h"
61 #include "rx/rx.h"
63 #include "sensors/acceleration.h"
64 #include "sensors/battery.h"
65 #include "sensors/gyro.h"
67 #include "scheduler/scheduler.h"
69 pidProfile_t *currentPidProfile;
71 #ifndef RX_SPI_DEFAULT_PROTOCOL
72 #define RX_SPI_DEFAULT_PROTOCOL 0
73 #endif
75 #define DYNAMIC_FILTER_MAX_SUPPORTED_LOOP_TIME HZ_TO_INTERVAL_US(2000)
77 PG_REGISTER_WITH_RESET_TEMPLATE(pilotConfig_t, pilotConfig, PG_PILOT_CONFIG, 1);
79 PG_RESET_TEMPLATE(pilotConfig_t, pilotConfig,
80 .name = { 0 },
81 .displayName = { 0 },
84 PG_REGISTER_WITH_RESET_TEMPLATE(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 2);
86 PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
87 .pidProfileIndex = 0,
88 .activeRateProfile = 0,
89 .debug_mode = DEBUG_MODE,
90 .task_statistics = true,
91 .cpu_overclock = 0,
92 .powerOnArmingGraceTime = 5,
93 .boardIdentifier = TARGET_BOARD_IDENTIFIER,
94 .hseMhz = SYSTEM_HSE_VALUE, // Not used for non-F4 targets
95 .configured = false,
96 .schedulerOptimizeRate = false,
99 uint8_t getCurrentPidProfileIndex(void)
101 return systemConfig()->pidProfileIndex;
104 static void loadPidProfile(void)
106 currentPidProfile = pidProfilesMutable(systemConfig()->pidProfileIndex);
109 uint8_t getCurrentControlRateProfileIndex(void)
111 return systemConfig()->activeRateProfile;
114 uint16_t getCurrentMinthrottle(void)
116 return motorConfig()->minthrottle;
119 void resetConfigs(void)
121 pgResetAll();
123 #if defined(USE_TARGET_CONFIG)
124 targetConfiguration();
125 #endif
128 static void activateConfig(void)
130 schedulerOptimizeRate(systemConfig()->schedulerOptimizeRate);
131 loadPidProfile();
132 loadControlRateProfile();
134 initRcProcessing();
136 resetAdjustmentStates();
138 pidInit(currentPidProfile);
140 rcControlsInit();
142 failsafeReset();
143 setAccelerationTrims(&accelerometerConfigMutable()->accZero);
144 accInitFilters();
146 imuConfigure(throttleCorrectionConfig()->throttle_correction_angle, throttleCorrectionConfig()->throttle_correction_value);
148 #ifdef USE_LED_STRIP
149 reevaluateLedConfig();
150 #endif
153 static void validateAndFixConfig(void)
155 #if !defined(USE_QUAD_MIXER_ONLY)
156 // Reset unsupported mixer mode to default.
157 // This check will be gone when motor/servo mixers are loaded dynamically
158 // by configurator as a part of configuration procedure.
160 mixerMode_e mixerMode = mixerConfigMutable()->mixerMode;
162 if (!(mixerMode == MIXER_CUSTOM || mixerMode == MIXER_CUSTOM_AIRPLANE || mixerMode == MIXER_CUSTOM_TRI)) {
163 if (mixers[mixerMode].motorCount && mixers[mixerMode].motor == NULL)
164 mixerConfigMutable()->mixerMode = MIXER_CUSTOM;
165 #ifdef USE_SERVOS
166 if (mixers[mixerMode].useServo && servoMixers[mixerMode].servoRuleCount == 0)
167 mixerConfigMutable()->mixerMode = MIXER_CUSTOM_AIRPLANE;
168 #endif
170 #endif
172 if (!isSerialConfigValid(serialConfig())) {
173 pgResetFn_serialConfig(serialConfigMutable());
176 #if defined(USE_GPS)
177 serialPortConfig_t *gpsSerial = findSerialPortConfig(FUNCTION_GPS);
178 if (gpsConfig()->provider == GPS_MSP && gpsSerial) {
179 serialRemovePort(gpsSerial->identifier);
181 #endif
182 if (
183 #if defined(USE_GPS)
184 gpsConfig()->provider != GPS_MSP && !gpsSerial &&
185 #endif
186 true) {
187 featureDisable(FEATURE_GPS);
190 if (systemConfig()->activeRateProfile >= CONTROL_RATE_PROFILE_COUNT) {
191 systemConfigMutable()->activeRateProfile = 0;
193 loadControlRateProfile();
195 if (systemConfig()->pidProfileIndex >= PID_PROFILE_COUNT) {
196 systemConfigMutable()->pidProfileIndex = 0;
198 loadPidProfile();
200 // Prevent invalid notch cutoff
201 if (currentPidProfile->dterm_notch_cutoff >= currentPidProfile->dterm_notch_hz) {
202 currentPidProfile->dterm_notch_hz = 0;
205 #ifdef USE_DYN_LPF
206 //PRevent invalid dynamic lowpass
207 if (currentPidProfile->dyn_lpf_dterm_min_hz > currentPidProfile->dyn_lpf_dterm_max_hz) {
208 currentPidProfile->dyn_lpf_dterm_min_hz = 0;
210 #endif
212 if (currentPidProfile->motor_output_limit > 100 || currentPidProfile->motor_output_limit == 0) {
213 currentPidProfile->motor_output_limit = 100;
216 if (currentPidProfile->auto_profile_cell_count > MAX_AUTO_DETECT_CELL_COUNT || currentPidProfile->auto_profile_cell_count < AUTO_PROFILE_CELL_COUNT_CHANGE) {
217 currentPidProfile->auto_profile_cell_count = AUTO_PROFILE_CELL_COUNT_STAY;
220 if (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_BRUSHED) {
221 featureDisable(FEATURE_3D);
223 if (motorConfig()->mincommand < 1000) {
224 motorConfigMutable()->mincommand = 1000;
228 if ((motorConfig()->dev.motorPwmProtocol == PWM_TYPE_STANDARD) && (motorConfig()->dev.motorPwmRate > BRUSHLESS_MOTORS_PWM_RATE)) {
229 motorConfigMutable()->dev.motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE;
232 validateAndFixGyroConfig();
234 if (!(featureIsEnabled(FEATURE_RX_PARALLEL_PWM) || featureIsEnabled(FEATURE_RX_PPM) || featureIsEnabled(FEATURE_RX_SERIAL) || featureIsEnabled(FEATURE_RX_MSP) || featureIsEnabled(FEATURE_RX_SPI))) {
235 featureEnable(DEFAULT_RX_FEATURE);
238 if (featureIsEnabled(FEATURE_RX_PPM)) {
239 featureDisable(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_SPI);
242 if (featureIsEnabled(FEATURE_RX_MSP)) {
243 featureDisable(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_SPI);
246 if (featureIsEnabled(FEATURE_RX_SERIAL)) {
247 featureDisable(FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
250 #ifdef USE_RX_SPI
251 if (featureIsEnabled(FEATURE_RX_SPI)) {
252 featureDisable(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_MSP);
254 #endif // USE_RX_SPI
256 if (featureIsEnabled(FEATURE_RX_PARALLEL_PWM)) {
257 featureDisable(FEATURE_RX_SERIAL | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
260 #ifdef USE_SOFTSPI
261 if (featureIsEnabled(FEATURE_SOFTSPI)) {
262 featureDisable(FEATURE_RX_PPM | FEATURE_RX_PARALLEL_PWM | FEATURE_SOFTSERIAL);
263 batteryConfigMutable()->voltageMeterSource = VOLTAGE_METER_NONE;
264 #if defined(STM32F10X)
265 featureDisable(FEATURE_LED_STRIP);
266 // rssi adc needs the same ports
267 featureDisable(FEATURE_RSSI_ADC);
268 // current meter needs the same ports
269 if (batteryConfig()->currentMeterSource == CURRENT_METER_ADC) {
270 batteryConfigMutable()->currentMeterSource = CURRENT_METER_NONE;
272 #endif // STM32F10X
274 #endif // USE_SOFTSPI
276 #if defined(USE_ADC)
277 if (featureIsEnabled(FEATURE_RSSI_ADC)) {
278 rxConfigMutable()->rssi_channel = 0;
279 rxConfigMutable()->rssi_src_frame_errors = false;
280 } else
281 #endif
282 if (rxConfigMutable()->rssi_channel
283 #if defined(USE_PWM) || defined(USE_PPM)
284 || featureIsEnabled(FEATURE_RX_PPM) || featureIsEnabled(FEATURE_RX_PARALLEL_PWM)
285 #endif
287 rxConfigMutable()->rssi_src_frame_errors = false;
290 if (!rcSmoothingIsEnabled() || rxConfig()->rcInterpolationChannels == INTERPOLATION_CHANNELS_T) {
291 for (unsigned i = 0; i < PID_PROFILE_COUNT; i++) {
292 pidProfilesMutable(i)->pid[PID_ROLL].F = 0;
293 pidProfilesMutable(i)->pid[PID_PITCH].F = 0;
297 if (!rcSmoothingIsEnabled() ||
298 (rxConfig()->rcInterpolationChannels != INTERPOLATION_CHANNELS_RPY &&
299 rxConfig()->rcInterpolationChannels != INTERPOLATION_CHANNELS_RPYT)) {
301 for (unsigned i = 0; i < PID_PROFILE_COUNT; i++) {
302 pidProfilesMutable(i)->pid[PID_YAW].F = 0;
306 #if defined(USE_THROTTLE_BOOST)
307 if (!rcSmoothingIsEnabled() ||
308 !(rxConfig()->rcInterpolationChannels == INTERPOLATION_CHANNELS_RPYT
309 || rxConfig()->rcInterpolationChannels == INTERPOLATION_CHANNELS_T
310 || rxConfig()->rcInterpolationChannels == INTERPOLATION_CHANNELS_RPT)) {
311 for (unsigned i = 0; i < PID_PROFILE_COUNT; i++) {
312 pidProfilesMutable(i)->throttle_boost = 0;
315 #endif
317 if (
318 featureIsEnabled(FEATURE_3D) || !featureIsEnabled(FEATURE_GPS)
319 #if !defined(USE_GPS) || !defined(USE_GPS_RESCUE)
320 || true
321 #endif
323 if (failsafeConfig()->failsafe_procedure == FAILSAFE_PROCEDURE_GPS_RESCUE) {
324 failsafeConfigMutable()->failsafe_procedure = FAILSAFE_PROCEDURE_DROP_IT;
327 if (isModeActivationConditionPresent(BOXGPSRESCUE)) {
328 removeModeActivationCondition(BOXGPSRESCUE);
332 #if defined(USE_ESC_SENSOR)
333 if (!findSerialPortConfig(FUNCTION_ESC_SENSOR)) {
334 featureDisable(FEATURE_ESC_SENSOR);
336 #endif
338 // clear features that are not supported.
339 // I have kept them all here in one place, some could be moved to sections of code above.
341 #ifndef USE_PPM
342 featureDisable(FEATURE_RX_PPM);
343 #endif
345 #ifndef USE_SERIAL_RX
346 featureDisable(FEATURE_RX_SERIAL);
347 #endif
349 #if !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL2)
350 featureDisable(FEATURE_SOFTSERIAL);
351 #endif
353 #ifndef USE_RANGEFINDER
354 featureDisable(FEATURE_RANGEFINDER);
355 #endif
357 #ifndef USE_TELEMETRY
358 featureDisable(FEATURE_TELEMETRY);
359 #endif
361 #ifndef USE_PWM
362 featureDisable(FEATURE_RX_PARALLEL_PWM);
363 #endif
365 #ifndef USE_RX_MSP
366 featureDisable(FEATURE_RX_MSP);
367 #endif
369 #ifndef USE_LED_STRIP
370 featureDisable(FEATURE_LED_STRIP);
371 #endif
373 #ifndef USE_DASHBOARD
374 featureDisable(FEATURE_DASHBOARD);
375 #endif
377 #ifndef USE_OSD
378 featureDisable(FEATURE_OSD);
379 #endif
381 #ifndef USE_SERVOS
382 featureDisable(FEATURE_SERVO_TILT | FEATURE_CHANNEL_FORWARDING);
383 #endif
385 #ifndef USE_TRANSPONDER
386 featureDisable(FEATURE_TRANSPONDER);
387 #endif
389 #ifndef USE_RX_SPI
390 featureDisable(FEATURE_RX_SPI);
391 #endif
393 #ifndef USE_SOFTSPI
394 featureDisable(FEATURE_SOFTSPI);
395 #endif
397 #ifndef USE_ESC_SENSOR
398 featureDisable(FEATURE_ESC_SENSOR);
399 #endif
401 #ifndef USE_GYRO_DATA_ANALYSE
402 featureDisable(FEATURE_DYNAMIC_FILTER);
403 #endif
405 #if !defined(USE_ADC)
406 featureDisable(FEATURE_RSSI_ADC);
407 #endif
409 #if defined(USE_BEEPER)
410 if (beeperDevConfig()->frequency && !timerGetByTag(beeperDevConfig()->ioTag)) {
411 beeperDevConfigMutable()->frequency = 0;
414 if (beeperConfig()->beeper_off_flags & ~BEEPER_ALLOWED_MODES) {
415 beeperConfigMutable()->beeper_off_flags = 0;
418 #ifdef USE_DSHOT
419 if (beeperConfig()->dshotBeaconOffFlags & ~DSHOT_BEACON_ALLOWED_MODES) {
420 beeperConfigMutable()->dshotBeaconOffFlags = 0;
423 if (beeperConfig()->dshotBeaconTone < DSHOT_CMD_BEACON1
424 || beeperConfig()->dshotBeaconTone > DSHOT_CMD_BEACON5) {
425 beeperConfigMutable()->dshotBeaconTone = DSHOT_CMD_BEACON1;
427 #endif
428 #endif
430 #if defined(USE_DSHOT_TELEMETRY)
431 if (motorConfig()->dev.useBurstDshot && motorConfig()->dev.useDshotTelemetry) {
432 motorConfigMutable()->dev.useDshotTelemetry = false;
434 #endif
436 #if defined(TARGET_VALIDATECONFIG)
437 targetValidateConfiguration();
438 #endif
441 void validateAndFixGyroConfig(void)
443 #ifdef USE_GYRO_DATA_ANALYSE
444 // Disable dynamic filter if gyro loop is less than 2KHz
445 if (gyro.targetLooptime > DYNAMIC_FILTER_MAX_SUPPORTED_LOOP_TIME) {
446 featureDisable(FEATURE_DYNAMIC_FILTER);
448 #endif
450 // Prevent invalid notch cutoff
451 if (gyroConfig()->gyro_soft_notch_cutoff_1 >= gyroConfig()->gyro_soft_notch_hz_1) {
452 gyroConfigMutable()->gyro_soft_notch_hz_1 = 0;
454 if (gyroConfig()->gyro_soft_notch_cutoff_2 >= gyroConfig()->gyro_soft_notch_hz_2) {
455 gyroConfigMutable()->gyro_soft_notch_hz_2 = 0;
457 #ifdef USE_DYN_LPF
458 //Prevent invalid dynamic lowpass filter
459 if (gyroConfig()->dyn_lpf_gyro_min_hz > gyroConfig()->dyn_lpf_gyro_max_hz) {
460 gyroConfigMutable()->dyn_lpf_gyro_min_hz = 0;
462 #endif
464 if (gyroConfig()->gyro_hardware_lpf == GYRO_HARDWARE_LPF_1KHZ_SAMPLE) {
465 pidConfigMutable()->pid_process_denom = 1; // When gyro set to 1khz always set pid speed 1:1 to sampling speed
466 gyroConfigMutable()->gyro_sync_denom = 1;
467 gyroConfigMutable()->gyro_use_32khz = false;
470 if (gyroConfig()->gyro_use_32khz) {
471 // F1 and F3 can't handle high sample speed.
472 #if defined(STM32F1)
473 gyroConfigMutable()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 16);
474 #elif defined(STM32F3)
475 gyroConfigMutable()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 4);
476 #endif
477 } else {
478 #if defined(STM32F1)
479 gyroConfigMutable()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 3);
480 #endif
483 float samplingTime;
484 switch (gyroMpuDetectionResult()->sensor) {
485 case ICM_20649_SPI:
486 samplingTime = 1.0f / 9000.0f;
487 break;
488 case BMI_160_SPI:
489 samplingTime = 0.0003125f;
490 break;
491 default:
492 samplingTime = 0.000125f;
493 break;
495 if (gyroConfig()->gyro_hardware_lpf == GYRO_HARDWARE_LPF_1KHZ_SAMPLE) {
496 switch (gyroMpuDetectionResult()->sensor) {
497 case ICM_20649_SPI:
498 samplingTime = 1.0f / 1100.0f;
499 break;
500 default:
501 samplingTime = 0.001f;
502 break;
505 if (gyroConfig()->gyro_use_32khz) {
506 samplingTime = 0.00003125;
509 // check for looptime restrictions based on motor protocol. Motor times have safety margin
510 float motorUpdateRestriction;
511 switch (motorConfig()->dev.motorPwmProtocol) {
512 case PWM_TYPE_STANDARD:
513 motorUpdateRestriction = 1.0f / BRUSHLESS_MOTORS_PWM_RATE;
514 break;
515 case PWM_TYPE_ONESHOT125:
516 motorUpdateRestriction = 0.0005f;
517 break;
518 case PWM_TYPE_ONESHOT42:
519 motorUpdateRestriction = 0.0001f;
520 break;
521 #ifdef USE_DSHOT
522 case PWM_TYPE_DSHOT150:
523 motorUpdateRestriction = 0.000250f;
524 break;
525 case PWM_TYPE_DSHOT300:
526 motorUpdateRestriction = 0.0001f;
527 break;
528 #endif
529 default:
530 motorUpdateRestriction = 0.00003125f;
531 break;
534 if (motorConfig()->dev.useUnsyncedPwm) {
535 // Prevent overriding the max rate of motors
536 if ((motorConfig()->dev.motorPwmProtocol <= PWM_TYPE_BRUSHED) && (motorConfig()->dev.motorPwmProtocol != PWM_TYPE_STANDARD)) {
537 const uint32_t maxEscRate = lrintf(1.0f / motorUpdateRestriction);
538 motorConfigMutable()->dev.motorPwmRate = MIN(motorConfig()->dev.motorPwmRate, maxEscRate);
540 } else {
541 const float pidLooptime = samplingTime * gyroConfig()->gyro_sync_denom * pidConfig()->pid_process_denom;
542 if (pidLooptime < motorUpdateRestriction) {
543 const uint8_t minPidProcessDenom = constrain(motorUpdateRestriction / (samplingTime * gyroConfig()->gyro_sync_denom), 1, MAX_PID_PROCESS_DENOM);
544 pidConfigMutable()->pid_process_denom = MAX(pidConfigMutable()->pid_process_denom, minPidProcessDenom);
548 #ifdef USE_BLACKBOX
549 #ifndef USE_FLASHFS
550 if (blackboxConfig()->device == 1) { // BLACKBOX_DEVICE_FLASH (but not defined)
551 blackboxConfigMutable()->device = BLACKBOX_DEVICE_NONE;
553 #endif // USE_FLASHFS
555 #ifndef USE_SDCARD
556 if (blackboxConfig()->device == 2) { // BLACKBOX_DEVICE_SDCARD (but not defined)
557 blackboxConfigMutable()->device = BLACKBOX_DEVICE_NONE;
559 #endif // USE_SDCARD
560 #endif // USE_BLACKBOX
563 bool readEEPROM(void)
565 suspendRxPwmPpmSignal();
567 // Sanity check, read flash
568 bool success = loadEEPROM();
570 validateAndFixConfig();
572 activateConfig();
574 resumeRxPwmPpmSignal();
576 return success;
579 static void ValidateAndWriteConfigToEEPROM(bool setConfigured)
581 validateAndFixConfig();
583 suspendRxPwmPpmSignal();
585 #ifdef USE_CONFIGURATION_STATE
586 if (setConfigured) {
587 systemConfigMutable()->configured = true;
589 #else
590 UNUSED(setConfigured);
591 #endif
593 writeConfigToEEPROM();
595 resumeRxPwmPpmSignal();
598 void writeEEPROM(void)
600 ValidateAndWriteConfigToEEPROM(true);
603 void writeEEPROMWithFeatures(uint32_t features)
605 featureDisableAll();
606 featureEnable(features);
608 ValidateAndWriteConfigToEEPROM(true);
611 void resetEEPROM(void)
613 resetConfigs();
615 ValidateAndWriteConfigToEEPROM(false);
617 activateConfig();
620 void ensureEEPROMStructureIsValid(void)
622 if (isEEPROMStructureValid()) {
623 return;
625 resetEEPROM();
628 void saveConfigAndNotify(void)
630 ValidateAndWriteConfigToEEPROM(true);
631 readEEPROM();
632 beeperConfirmationBeeps(1);
635 void changePidProfileFromCellCount(uint8_t cellCount)
637 if (currentPidProfile->auto_profile_cell_count == cellCount || currentPidProfile->auto_profile_cell_count == AUTO_PROFILE_CELL_COUNT_STAY) {
638 return;
641 unsigned profileIndex = (systemConfig()->pidProfileIndex + 1) % PID_PROFILE_COUNT;
642 int matchingProfileIndex = -1;
643 while (profileIndex != systemConfig()->pidProfileIndex) {
644 if (pidProfiles(profileIndex)->auto_profile_cell_count == cellCount) {
645 matchingProfileIndex = profileIndex;
647 break;
648 } else if (matchingProfileIndex < 0 && pidProfiles(profileIndex)->auto_profile_cell_count == AUTO_PROFILE_CELL_COUNT_STAY) {
649 matchingProfileIndex = profileIndex;
652 profileIndex = (profileIndex + 1) % PID_PROFILE_COUNT;
655 if (matchingProfileIndex >= 0) {
656 changePidProfile(matchingProfileIndex);
660 void changePidProfile(uint8_t pidProfileIndex)
662 if (pidProfileIndex < PID_PROFILE_COUNT) {
663 systemConfigMutable()->pidProfileIndex = pidProfileIndex;
664 loadPidProfile();
666 pidInit(currentPidProfile);
669 beeperConfirmationBeeps(pidProfileIndex + 1);
672 bool isSystemConfigured(void)
674 #ifdef USE_CONFIGURATION_STATE
675 return systemConfig()->configured;
676 #else
677 return true;
678 #endif