Improved initialisation order. Stopped calling pidInit before gyro detected (#4218)
[betaflight.git] / src / main / fc / config.c
blob820f9258c429e31844ad27d5ed643a5ce22525e5
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #include <stdbool.h>
19 #include <stdint.h>
20 #include <string.h>
21 #include <math.h>
23 #include "platform.h"
25 #include "build/build_config.h"
26 #include "build/debug.h"
28 #include "blackbox/blackbox_io.h"
30 #include "cms/cms.h"
32 #include "common/axis.h"
33 #include "common/color.h"
34 #include "common/filter.h"
35 #include "common/maths.h"
37 #include "config/config_eeprom.h"
38 #include "config/feature.h"
39 #include "config/parameter_group.h"
40 #include "config/parameter_group_ids.h"
42 #include "drivers/accgyro/accgyro.h"
43 #include "drivers/bus_spi.h"
44 #include "drivers/compass/compass.h"
45 #include "drivers/inverter.h"
46 #include "drivers/io.h"
47 #include "drivers/light_led.h"
48 #include "drivers/light_ws2811strip.h"
49 #include "drivers/max7456.h"
50 #include "drivers/pwm_esc_detect.h"
51 #include "drivers/pwm_output.h"
52 #include "drivers/rx_pwm.h"
53 #include "drivers/rx_spi.h"
54 #include "drivers/sdcard.h"
55 #include "drivers/sensor.h"
56 #include "drivers/sonar_hcsr04.h"
57 #include "drivers/sound_beeper.h"
58 #include "drivers/system.h"
59 #include "drivers/timer.h"
60 #include "drivers/vcd.h"
62 #include "fc/config.h"
63 #include "fc/controlrate_profile.h"
64 #include "fc/fc_core.h"
65 #include "fc/fc_rc.h"
66 #include "fc/rc_adjustments.h"
67 #include "fc/rc_controls.h"
68 #include "fc/runtime_config.h"
70 #include "flight/altitude.h"
71 #include "flight/failsafe.h"
72 #include "flight/imu.h"
73 #include "flight/mixer.h"
74 #include "flight/navigation.h"
75 #include "flight/pid.h"
76 #include "flight/servos.h"
78 #include "io/beeper.h"
79 #include "io/gimbal.h"
80 #include "io/gps.h"
81 #include "io/ledstrip.h"
82 #include "io/motors.h"
83 #include "io/osd.h"
84 #include "io/serial.h"
85 #include "io/servos.h"
86 #include "io/vtx_control.h"
88 #include "rx/rx.h"
89 #include "rx/rx_spi.h"
91 #include "sensors/acceleration.h"
92 #include "sensors/barometer.h"
93 #include "sensors/battery.h"
94 #include "sensors/boardalignment.h"
95 #include "sensors/compass.h"
96 #include "sensors/gyro.h"
97 #include "sensors/sensors.h"
99 #include "telemetry/telemetry.h"
101 #ifndef USE_OSD_SLAVE
102 pidProfile_t *currentPidProfile;
103 #endif
105 #ifndef DEFAULT_FEATURES
106 #define DEFAULT_FEATURES 0
107 #endif
108 #ifndef DEFAULT_RX_FEATURE
109 #define DEFAULT_RX_FEATURE FEATURE_RX_PARALLEL_PWM
110 #endif
111 #ifndef RX_SPI_DEFAULT_PROTOCOL
112 #define RX_SPI_DEFAULT_PROTOCOL 0
113 #endif
115 PG_REGISTER_WITH_RESET_TEMPLATE(featureConfig_t, featureConfig, PG_FEATURE_CONFIG, 0);
117 PG_RESET_TEMPLATE(featureConfig_t, featureConfig,
118 .enabledFeatures = DEFAULT_FEATURES | DEFAULT_RX_FEATURE
121 PG_REGISTER_WITH_RESET_TEMPLATE(pilotConfig_t, pilotConfig, PG_PILOT_CONFIG, 0);
123 PG_RESET_TEMPLATE(pilotConfig_t, pilotConfig,
124 .name = { 0 }
127 PG_REGISTER_WITH_RESET_TEMPLATE(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 1);
129 #ifndef USE_OSD_SLAVE
130 #if defined(STM32F4) && !defined(DISABLE_OVERCLOCK)
131 PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
132 .pidProfileIndex = 0,
133 .activeRateProfile = 0,
134 .debug_mode = DEBUG_MODE,
135 .task_statistics = true,
136 .cpu_overclock = false,
137 .powerOnArmingGraceTime = 5,
138 .boardIdentifier = TARGET_BOARD_IDENTIFIER
140 #else
141 PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
142 .pidProfileIndex = 0,
143 .activeRateProfile = 0,
144 .debug_mode = DEBUG_MODE,
145 .task_statistics = true,
146 .boardIdentifier = TARGET_BOARD_IDENTIFIER
148 #endif
149 #endif
151 #ifdef USE_OSD_SLAVE
152 PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
153 .debug_mode = DEBUG_MODE,
154 .task_statistics = true,
155 .boardIdentifier = TARGET_BOARD_IDENTIFIER
157 #endif
159 #ifdef USE_ADC
160 PG_REGISTER_WITH_RESET_FN(adcConfig_t, adcConfig, PG_ADC_CONFIG, 0);
161 #endif
162 #ifdef USE_PWM
163 PG_REGISTER_WITH_RESET_FN(pwmConfig_t, pwmConfig, PG_PWM_CONFIG, 0);
164 #endif
165 #ifdef USE_PPM
166 PG_REGISTER_WITH_RESET_FN(ppmConfig_t, ppmConfig, PG_PPM_CONFIG, 0);
167 #endif
169 #ifdef USE_FLASHFS
170 PG_REGISTER_WITH_RESET_FN(flashConfig_t, flashConfig, PG_FLASH_CONFIG, 0);
172 void pgResetFn_flashConfig(flashConfig_t *flashConfig)
174 #ifdef M25P16_CS_PIN
175 flashConfig->csTag = IO_TAG(M25P16_CS_PIN);
176 #else
177 flashConfig->csTag = IO_TAG_NONE;
178 #endif
179 flashConfig->spiDevice = SPI_DEV_TO_CFG(spiDeviceByInstance(M25P16_SPI_INSTANCE));
181 #endif // USE_FLASH_FS
183 #ifdef USE_SDCARD
184 PG_REGISTER_WITH_RESET_TEMPLATE(sdcardConfig_t, sdcardConfig, PG_SDCARD_CONFIG, 0);
186 PG_RESET_TEMPLATE(sdcardConfig_t, sdcardConfig,
187 .useDma = false
189 #endif // USE_SDCARD
191 // no template required since defaults are zero
192 PG_REGISTER(vcdProfile_t, vcdProfile, PG_VCD_CONFIG, 0);
194 #ifdef USE_ADC
195 void pgResetFn_adcConfig(adcConfig_t *adcConfig)
197 #ifdef VBAT_ADC_PIN
198 adcConfig->vbat.enabled = true;
199 adcConfig->vbat.ioTag = IO_TAG(VBAT_ADC_PIN);
200 #endif
202 #ifdef EXTERNAL1_ADC_PIN
203 adcConfig->external1.enabled = true;
204 adcConfig->external1.ioTag = IO_TAG(EXTERNAL1_ADC_PIN);
205 #endif
207 #ifdef CURRENT_METER_ADC_PIN
208 adcConfig->current.enabled = true;
209 adcConfig->current.ioTag = IO_TAG(CURRENT_METER_ADC_PIN);
210 #endif
212 #ifdef RSSI_ADC_PIN
213 adcConfig->rssi.enabled = true;
214 adcConfig->rssi.ioTag = IO_TAG(RSSI_ADC_PIN);
215 #endif
218 #endif // USE_ADC
221 #if defined(USE_PWM) || defined(USE_PPM)
222 void pgResetFn_ppmConfig(ppmConfig_t *ppmConfig)
224 #ifdef PPM_PIN
225 ppmConfig->ioTag = IO_TAG(PPM_PIN);
226 #else
227 for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
228 if (timerHardware[i].usageFlags & TIM_USE_PPM) {
229 ppmConfig->ioTag = timerHardware[i].tag;
230 return;
234 ppmConfig->ioTag = IO_TAG_NONE;
235 #endif
238 void pgResetFn_pwmConfig(pwmConfig_t *pwmConfig)
240 pwmConfig->inputFilteringMode = INPUT_FILTERING_DISABLED;
241 int inputIndex = 0;
242 for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT && inputIndex < PWM_INPUT_PORT_COUNT; i++) {
243 if (timerHardware[i].usageFlags & TIM_USE_PWM) {
244 pwmConfig->ioTags[inputIndex] = timerHardware[i].tag;
245 inputIndex++;
249 #endif
251 #ifdef SWAP_SERIAL_PORT_0_AND_1_DEFAULTS
252 #define FIRST_PORT_INDEX 1
253 #define SECOND_PORT_INDEX 0
254 #else
255 #define FIRST_PORT_INDEX 0
256 #define SECOND_PORT_INDEX 1
257 #endif
259 #ifndef USE_OSD_SLAVE
260 uint8_t getCurrentPidProfileIndex(void)
262 return systemConfig()->pidProfileIndex;
265 static void setPidProfile(uint8_t pidProfileIndex)
267 if (pidProfileIndex < MAX_PROFILE_COUNT) {
268 systemConfigMutable()->pidProfileIndex = pidProfileIndex;
269 currentPidProfile = pidProfilesMutable(pidProfileIndex);
273 uint8_t getCurrentControlRateProfileIndex(void)
275 return systemConfigMutable()->activeRateProfile;
278 uint16_t getCurrentMinthrottle(void)
280 return motorConfig()->minthrottle;
282 #endif
284 void resetConfigs(void)
286 pgResetAll();
288 #if defined(TARGET_CONFIG)
289 targetConfiguration();
290 #endif
292 #ifndef USE_OSD_SLAVE
293 setPidProfile(0);
294 setControlRateProfile(0);
295 #endif
297 #ifdef LED_STRIP
298 reevaluateLedConfig();
299 #endif
302 void activateConfig(void)
304 #ifndef USE_OSD_SLAVE
305 generateThrottleCurve();
307 resetAdjustmentStates();
309 pidInit(currentPidProfile);
310 useRcControlsConfig(currentPidProfile);
311 useAdjustmentConfig(currentPidProfile);
313 #ifdef GPS
314 gpsUsePIDs(currentPidProfile);
315 #endif
317 failsafeReset();
318 setAccelerationTrims(&accelerometerConfigMutable()->accZero);
319 setAccelerationFilter(accelerometerConfig()->acc_lpf_hz);
321 imuConfigure(throttleCorrectionConfig()->throttle_correction_angle);
322 #endif
325 void validateAndFixConfig(void)
327 #if !defined(USE_QUAD_MIXER_ONLY) && !defined(USE_OSD_SLAVE)
328 // Reset unsupported mixer mode to default.
329 // This check will be gone when motor/servo mixers are loaded dynamically
330 // by configurator as a part of configuration procedure.
332 mixerMode_e mixerMode = mixerConfigMutable()->mixerMode;
334 if (!(mixerMode == MIXER_CUSTOM || mixerMode == MIXER_CUSTOM_AIRPLANE || mixerMode == MIXER_CUSTOM_TRI)) {
335 if (mixers[mixerMode].motorCount && mixers[mixerMode].motor == NULL)
336 mixerConfigMutable()->mixerMode = MIXER_CUSTOM;
337 #ifdef USE_SERVOS
338 if (mixers[mixerMode].useServo && servoMixers[mixerMode].servoRuleCount == 0)
339 mixerConfigMutable()->mixerMode = MIXER_CUSTOM_AIRPLANE;
340 #endif
342 #endif
344 #ifndef USE_OSD_SLAVE
345 if (systemConfig()->activeRateProfile >= CONTROL_RATE_PROFILE_COUNT) {
346 systemConfigMutable()->activeRateProfile = 0;
348 if (systemConfig()->pidProfileIndex >= MAX_PROFILE_COUNT) {
349 systemConfigMutable()->pidProfileIndex = 0;
352 if ((motorConfig()->dev.motorPwmProtocol == PWM_TYPE_BRUSHED) && (motorConfig()->mincommand < 1000)) {
353 motorConfigMutable()->mincommand = 1000;
356 if ((motorConfig()->dev.motorPwmProtocol == PWM_TYPE_STANDARD) && (motorConfig()->dev.motorPwmRate > BRUSHLESS_MOTORS_PWM_RATE)) {
357 motorConfigMutable()->dev.motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE;
360 if (!(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_SERIAL) || featureConfigured(FEATURE_RX_MSP) || featureConfigured(FEATURE_RX_SPI))) {
361 featureSet(DEFAULT_RX_FEATURE);
364 if (featureConfigured(FEATURE_RX_PPM)) {
365 featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_SPI);
368 if (featureConfigured(FEATURE_RX_MSP)) {
369 featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_SPI);
372 if (featureConfigured(FEATURE_RX_SERIAL)) {
373 featureClear(FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
376 #ifdef USE_RX_SPI
377 if (featureConfigured(FEATURE_RX_SPI)) {
378 featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_MSP);
380 #endif // USE_RX_SPI
382 if (featureConfigured(FEATURE_RX_PARALLEL_PWM)) {
383 featureClear(FEATURE_RX_SERIAL | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
384 #if defined(STM32F10X)
385 // rssi adc needs the same ports
386 featureClear(FEATURE_RSSI_ADC);
387 // current meter needs the same ports
388 if (batteryConfig()->currentMeterSource == CURRENT_METER_ADC) {
389 batteryConfigMutable()->currentMeterSource = CURRENT_METER_NONE;
391 #endif // STM32F10X
392 // software serial needs free PWM ports
393 featureClear(FEATURE_SOFTSERIAL);
396 #ifdef USE_SOFTSPI
397 if (featureConfigured(FEATURE_SOFTSPI)) {
398 featureClear(FEATURE_RX_PPM | FEATURE_RX_PARALLEL_PWM | FEATURE_SOFTSERIAL);
399 batteryConfigMutable()->voltageMeterSource = VOLTAGE_METER_NONE;
400 #if defined(STM32F10X)
401 featureClear(FEATURE_LED_STRIP);
402 // rssi adc needs the same ports
403 featureClear(FEATURE_RSSI_ADC);
404 // current meter needs the same ports
405 if (batteryConfig()->currentMeterSource == CURRENT_METER_ADC) {
406 batteryConfigMutable()->currentMeterSource = CURRENT_METER_NONE;
408 #endif // STM32F10X
410 #endif // USE_SOFTSPI
412 // Prevent invalid notch cutoff
413 if (currentPidProfile->dterm_notch_cutoff >= currentPidProfile->dterm_notch_hz) {
414 currentPidProfile->dterm_notch_hz = 0;
417 validateAndFixGyroConfig();
418 #endif // USE_OSD_SLAVE
420 if (!isSerialConfigValid(serialConfig())) {
421 pgResetFn_serialConfig(serialConfigMutable());
424 // clear features that are not supported.
425 // I have kept them all here in one place, some could be moved to sections of code above.
427 #ifndef USE_PPM
428 featureClear(FEATURE_RX_PPM);
429 #endif
431 #ifndef SERIAL_RX
432 featureClear(FEATURE_RX_SERIAL);
433 #endif
435 #if !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL2)
436 featureClear(FEATURE_SOFTSERIAL);
437 #endif
439 #ifndef GPS
440 featureClear(FEATURE_GPS);
441 #endif
443 #ifndef SONAR
444 featureClear(FEATURE_SONAR);
445 #endif
447 #ifndef TELEMETRY
448 featureClear(FEATURE_TELEMETRY);
449 #endif
451 #ifndef USE_PWM
452 featureClear(FEATURE_RX_PARALLEL_PWM);
453 #endif
455 #ifndef USE_RX_MSP
456 featureClear(FEATURE_RX_MSP);
457 #endif
459 #ifndef LED_STRIP
460 featureClear(FEATURE_LED_STRIP);
461 #endif
463 #ifndef USE_DASHBOARD
464 featureClear(FEATURE_DASHBOARD);
465 #endif
467 #ifndef OSD
468 featureClear(FEATURE_OSD);
469 #endif
471 #ifndef USE_SERVOS
472 featureClear(FEATURE_SERVO_TILT | FEATURE_CHANNEL_FORWARDING);
473 #endif
475 #ifndef TRANSPONDER
476 featureClear(FEATURE_TRANSPONDER);
477 #endif
479 #ifndef USE_RX_SPI
480 featureClear(FEATURE_RX_SPI);
481 #endif
483 #ifndef USE_SOFTSPI
484 featureClear(FEATURE_SOFTSPI);
485 #endif
487 #ifndef USE_ESC_SENSOR
488 featureClear(FEATURE_ESC_SENSOR);
489 #endif
491 #ifndef USE_GYRO_DATA_ANALYSE
492 featureClear(FEATURE_DYNAMIC_FILTER);
493 #endif
495 #if defined(TARGET_VALIDATECONFIG)
496 targetValidateConfiguration();
497 #endif
500 #ifndef USE_OSD_SLAVE
501 void validateAndFixGyroConfig(void)
503 // Prevent invalid notch cutoff
504 if (gyroConfig()->gyro_soft_notch_cutoff_1 >= gyroConfig()->gyro_soft_notch_hz_1) {
505 gyroConfigMutable()->gyro_soft_notch_hz_1 = 0;
507 if (gyroConfig()->gyro_soft_notch_cutoff_2 >= gyroConfig()->gyro_soft_notch_hz_2) {
508 gyroConfigMutable()->gyro_soft_notch_hz_2 = 0;
512 if (gyroConfig()->gyro_lpf != GYRO_LPF_256HZ && gyroConfig()->gyro_lpf != GYRO_LPF_NONE) {
513 pidConfigMutable()->pid_process_denom = 1; // When gyro set to 1khz always set pid speed 1:1 to sampling speed
514 gyroConfigMutable()->gyro_sync_denom = 1;
515 gyroConfigMutable()->gyro_use_32khz = false;
518 if (gyroConfig()->gyro_use_32khz) {
519 // F1 and F3 can't handle high sample speed.
520 #if defined(STM32F1)
521 gyroConfigMutable()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 16);
522 #elif defined(STM32F3)
523 gyroConfigMutable()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 4);
524 #endif
525 } else {
526 #if defined(STM32F1)
527 gyroConfigMutable()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 3);
528 #endif
531 float samplingTime;
532 switch (gyroMpuDetectionResult()->sensor) {
533 case ICM_20649_SPI:
534 samplingTime = 1.0f / 9000.0f;
535 break;
536 case BMI_160_SPI:
537 samplingTime = 0.0003125f;
538 break;
539 default:
540 samplingTime = 0.000125f;
541 break;
544 if (gyroConfig()->gyro_lpf != GYRO_LPF_256HZ && gyroConfig()->gyro_lpf != GYRO_LPF_NONE) {
545 switch (gyroMpuDetectionResult()->sensor) {
546 case ICM_20649_SPI:
547 samplingTime = 1.0f / 1100.0f;
548 break;
549 default:
550 samplingTime = 0.001f;
551 break;
555 if (gyroConfig()->gyro_use_32khz) {
556 samplingTime = 0.00003125;
559 // check for looptime restrictions based on motor protocol. Motor times have safety margin
560 float motorUpdateRestriction;
561 switch (motorConfig()->dev.motorPwmProtocol) {
562 case (PWM_TYPE_STANDARD):
563 motorUpdateRestriction = 1.0f / BRUSHLESS_MOTORS_PWM_RATE;
564 break;
565 case (PWM_TYPE_ONESHOT125):
566 motorUpdateRestriction = 0.0005f;
567 break;
568 case (PWM_TYPE_ONESHOT42):
569 motorUpdateRestriction = 0.0001f;
570 break;
571 #ifdef USE_DSHOT
572 case (PWM_TYPE_DSHOT150):
573 motorUpdateRestriction = 0.000250f;
574 break;
575 case (PWM_TYPE_DSHOT300):
576 motorUpdateRestriction = 0.0001f;
577 break;
578 #endif
579 default:
580 motorUpdateRestriction = 0.00003125f;
583 if (!motorConfig()->dev.useUnsyncedPwm) {
584 const float pidLooptime = samplingTime * gyroConfig()->gyro_sync_denom * pidConfig()->pid_process_denom;
585 if (pidLooptime < motorUpdateRestriction) {
586 const uint8_t minPidProcessDenom = constrain(motorUpdateRestriction / (samplingTime * gyroConfig()->gyro_sync_denom), 1, MAX_PID_PROCESS_DENOM);
588 pidConfigMutable()->pid_process_denom = MAX(pidConfigMutable()->pid_process_denom, minPidProcessDenom);
590 } else {
591 // Prevent overriding the max rate of motors
592 if ((motorConfig()->dev.motorPwmProtocol <= PWM_TYPE_BRUSHED) && (motorConfig()->dev.motorPwmProtocol != PWM_TYPE_STANDARD)) {
593 const uint32_t maxEscRate = lrintf(1.0f / motorUpdateRestriction);
595 motorConfigMutable()->dev.motorPwmRate = MIN(motorConfig()->dev.motorPwmRate, maxEscRate);
599 #endif
601 void readEEPROM(void)
603 #ifndef USE_OSD_SLAVE
604 suspendRxSignal();
605 #endif
607 // Sanity check, read flash
608 if (!loadEEPROM()) {
609 failureMode(FAILURE_INVALID_EEPROM_CONTENTS);
612 validateAndFixConfig();
613 #ifndef USE_OSD_SLAVE
614 setControlRateProfile(systemConfig()->activeRateProfile);
615 setPidProfile(systemConfig()->pidProfileIndex);
616 #endif
617 activateConfig();
619 #ifndef USE_OSD_SLAVE
620 resumeRxSignal();
621 #endif
624 void writeEEPROM(void)
626 #ifndef USE_OSD_SLAVE
627 suspendRxSignal();
628 #endif
630 writeConfigToEEPROM();
632 #ifndef USE_OSD_SLAVE
633 resumeRxSignal();
634 #endif
637 void resetEEPROM(void)
639 resetConfigs();
640 writeEEPROM();
643 void ensureEEPROMContainsValidData(void)
645 if (isEEPROMContentValid()) {
646 return;
648 resetEEPROM();
651 void saveConfigAndNotify(void)
653 writeEEPROM();
654 readEEPROM();
655 beeperConfirmationBeeps(1);
658 #ifndef USE_OSD_SLAVE
659 void changePidProfile(uint8_t pidProfileIndex)
661 if (pidProfileIndex >= MAX_PROFILE_COUNT) {
662 pidProfileIndex = MAX_PROFILE_COUNT - 1;
664 systemConfigMutable()->pidProfileIndex = pidProfileIndex;
665 currentPidProfile = pidProfilesMutable(pidProfileIndex);
666 beeperConfirmationBeeps(pidProfileIndex + 1);
668 #endif
670 void beeperOffSet(uint32_t mask)
672 #ifdef BEEPER
673 beeperConfigMutable()->beeper_off_flags |= mask;
674 #else
675 UNUSED(mask);
676 #endif
679 void beeperOffSetAll(uint8_t beeperCount)
681 #ifdef BEEPER
682 beeperConfigMutable()->beeper_off_flags = (1 << beeperCount) -1;
683 #else
684 UNUSED(beeperCount);
685 #endif
688 void beeperOffClear(uint32_t mask)
690 #ifdef BEEPER
691 beeperConfigMutable()->beeper_off_flags &= ~(mask);
692 #else
693 UNUSED(mask);
694 #endif
697 void beeperOffClearAll(void)
699 #ifdef BEEPER
700 beeperConfigMutable()->beeper_off_flags = 0;
701 #endif
704 uint32_t getBeeperOffMask(void)
706 #ifdef BEEPER
707 return beeperConfig()->beeper_off_flags;
708 #else
709 return 0;
710 #endif
713 void setBeeperOffMask(uint32_t mask)
715 #ifdef BEEPER
716 beeperConfigMutable()->beeper_off_flags = mask;
717 #else
718 UNUSED(mask);
719 #endif
722 uint32_t getPreferredBeeperOffMask(void)
724 #ifdef BEEPER
725 return beeperConfig()->preferred_beeper_off_flags;
726 #else
727 return 0;
728 #endif
731 void setPreferredBeeperOffMask(uint32_t mask)
733 #ifdef BEEPER
734 beeperConfigMutable()->preferred_beeper_off_flags = mask;
735 #else
736 UNUSED(mask);
737 #endif