Moved osdDisplayPortDevice_e osdDisplayPortDevice initialisation to within USE_OSD...
[betaflight.git] / src / main / fc / init.c
blobc08471b30d3633acc4d1514feaecd8927eda49c7
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/build_config.h"
31 #include "build/debug.h"
32 #include "build/debug_pin.h"
34 #include "cms/cms.h"
35 #include "cms/cms_types.h"
37 #include "common/axis.h"
38 #include "common/color.h"
39 #include "common/maths.h"
40 #include "common/printf_serial.h"
42 #include "config/config.h"
43 #include "config/config_eeprom.h"
44 #include "config/feature.h"
46 #include "drivers/accgyro/accgyro.h"
47 #include "drivers/adc.h"
48 #include "drivers/bus.h"
49 #include "drivers/bus_i2c.h"
50 #include "drivers/bus_quadspi.h"
51 #include "drivers/bus_spi.h"
52 #include "drivers/buttons.h"
53 #include "drivers/camera_control.h"
54 #include "drivers/compass/compass.h"
55 #include "drivers/dma.h"
56 #include "drivers/exti.h"
57 #include "drivers/flash.h"
58 #include "drivers/inverter.h"
59 #include "drivers/io.h"
60 #include "drivers/light_led.h"
61 #include "drivers/mco.h"
62 #include "drivers/nvic.h"
63 #include "drivers/persistent.h"
64 #include "drivers/pin_pull_up_down.h"
65 #include "drivers/pwm_esc_detect.h"
66 #include "drivers/pwm_output.h"
67 #include "drivers/rx/rx_pwm.h"
68 #include "drivers/sensor.h"
69 #include "drivers/serial.h"
70 #include "drivers/serial_softserial.h"
71 #include "drivers/serial_uart.h"
72 #include "drivers/sdcard.h"
73 #include "drivers/sdio.h"
74 #include "drivers/sound_beeper.h"
75 #include "drivers/system.h"
76 #include "drivers/time.h"
77 #include "drivers/timer.h"
78 #include "drivers/transponder_ir.h"
79 #include "drivers/usb_io.h"
80 #ifdef USE_USB_MSC
81 #include "drivers/usb_msc.h"
82 #endif
83 #include "drivers/vtx_common.h"
84 #include "drivers/vtx_rtc6705.h"
85 #include "drivers/vtx_table.h"
87 #include "fc/board_info.h"
88 #include "fc/dispatch.h"
89 #include "fc/init.h"
90 #include "fc/rc_controls.h"
91 #include "fc/runtime_config.h"
92 #include "fc/stats.h"
93 #include "fc/tasks.h"
95 #include "flight/failsafe.h"
96 #include "flight/imu.h"
97 #include "flight/mixer.h"
98 #include "flight/gps_rescue.h"
99 #include "flight/pid.h"
100 #include "flight/pid_init.h"
101 #include "flight/position.h"
102 #include "flight/servos.h"
104 #include "io/asyncfatfs/asyncfatfs.h"
105 #include "io/beeper.h"
106 #include "io/dashboard.h"
107 #include "io/displayport_frsky_osd.h"
108 #include "io/displayport_max7456.h"
109 #include "io/displayport_msp.h"
110 #include "io/flashfs.h"
111 #include "io/gimbal.h"
112 #include "io/gps.h"
113 #include "io/ledstrip.h"
114 #include "io/pidaudio.h"
115 #include "io/piniobox.h"
116 #include "io/rcdevice_cam.h"
117 #include "io/serial.h"
118 #include "io/servos.h"
119 #include "io/transponder_ir.h"
120 #include "io/vtx.h"
121 #include "io/vtx_control.h"
122 #include "io/vtx_msp.h"
123 #include "io/vtx_rtc6705.h"
124 #include "io/vtx_smartaudio.h"
125 #include "io/vtx_tramp.h"
127 #include "msc/emfat_file.h"
128 #ifdef USE_PERSISTENT_MSC_RTC
129 #include "msc/usbd_storage.h"
130 #endif
132 #include "msp/msp.h"
133 #include "msp/msp_serial.h"
135 #include "osd/osd.h"
137 #include "pg/adc.h"
138 #include "pg/beeper.h"
139 #include "pg/beeper_dev.h"
140 #include "pg/bus_i2c.h"
141 #include "pg/bus_spi.h"
142 #include "pg/bus_quadspi.h"
143 #include "pg/flash.h"
144 #include "pg/mco.h"
145 #include "pg/motor.h"
146 #include "pg/pinio.h"
147 #include "pg/piniobox.h"
148 #include "pg/pin_pull_up_down.h"
149 #include "pg/pg.h"
150 #include "pg/rx.h"
151 #include "pg/rx_pwm.h"
152 #include "pg/rx_spi.h"
153 #include "pg/sdcard.h"
154 #include "pg/vcd.h"
155 #include "pg/vtx_io.h"
157 #include "rx/rx.h"
158 #include "rx/spektrum.h"
160 #include "scheduler/scheduler.h"
162 #include "sensors/acceleration.h"
163 #include "sensors/barometer.h"
164 #include "sensors/battery.h"
165 #include "sensors/boardalignment.h"
166 #include "sensors/compass.h"
167 #include "sensors/esc_sensor.h"
168 #include "sensors/gyro.h"
169 #include "sensors/gyro_init.h"
170 #include "sensors/initialisation.h"
172 #include "telemetry/telemetry.h"
174 #ifdef USE_HARDWARE_REVISION_DETECTION
175 #include "hardware_revision.h"
176 #endif
178 #ifdef TARGET_PREINIT
179 void targetPreInit(void);
180 #endif
182 uint8_t systemState = SYSTEM_STATE_INITIALISING;
184 #ifdef BUS_SWITCH_PIN
185 void busSwitchInit(void)
187 IO_t busSwitchResetPin = IO_NONE;
189 busSwitchResetPin = IOGetByTag(IO_TAG(BUS_SWITCH_PIN));
190 IOInit(busSwitchResetPin, OWNER_SYSTEM, 0);
191 IOConfigGPIO(busSwitchResetPin, IOCFG_OUT_PP);
193 // ENABLE
194 IOLo(busSwitchResetPin);
196 #endif
199 static void configureSPIAndQuadSPI(void)
201 #ifdef USE_SPI
202 spiPinConfigure(spiPinConfig(0));
203 #endif
205 sensorsPreInit();
207 #ifdef USE_SPI
208 spiPreinit();
210 #ifdef USE_SPI_DEVICE_1
211 spiInit(SPIDEV_1);
212 #endif
213 #ifdef USE_SPI_DEVICE_2
214 spiInit(SPIDEV_2);
215 #endif
216 #ifdef USE_SPI_DEVICE_3
217 spiInit(SPIDEV_3);
218 #endif
219 #ifdef USE_SPI_DEVICE_4
220 spiInit(SPIDEV_4);
221 #endif
222 #ifdef USE_SPI_DEVICE_5
223 spiInit(SPIDEV_5);
224 #endif
225 #ifdef USE_SPI_DEVICE_6
226 spiInit(SPIDEV_6);
227 #endif
228 #endif // USE_SPI
230 #ifdef USE_QUADSPI
231 quadSpiPinConfigure(quadSpiConfig(0));
233 #ifdef USE_QUADSPI_DEVICE_1
234 quadSpiInit(QUADSPIDEV_1);
235 #endif
236 #endif // USE_QUAD_SPI
239 #ifdef USE_SDCARD
240 static void sdCardAndFSInit(void)
242 sdcard_init(sdcardConfig());
243 afatfs_init();
245 #endif
247 static void swdPinsInit(void)
249 IO_t io = IOGetByTag(DEFIO_TAG_E(PA13)); // SWDIO
250 if (IOGetOwner(io) == OWNER_FREE) {
251 IOInit(io, OWNER_SWD, 0);
253 io = IOGetByTag(DEFIO_TAG_E(PA14)); // SWCLK
254 if (IOGetOwner(io) == OWNER_FREE) {
255 IOInit(io, OWNER_SWD, 0);
259 void init(void)
261 #ifdef SERIAL_PORT_COUNT
262 printfSerialInit();
263 #endif
265 systemInit();
267 // Initialize task data as soon as possible. Has to be done before tasksInit(),
268 // and any init code that may try to modify task behaviour before tasksInit().
269 tasksInitData();
271 // initialize IO (needed for all IO operations)
272 IOInitGlobal();
274 #ifdef USE_HARDWARE_REVISION_DETECTION
275 detectHardwareRevision();
276 #endif
278 #if defined(USE_TARGET_CONFIG)
279 // Call once before the config is loaded for any target specific configuration required to support loading the config
280 targetConfiguration();
281 #endif
283 #ifdef USE_BRUSHED_ESC_AUTODETECT
284 // Opportunistically use the first motor pin of the default configuration for detection.
285 // We are doing this as with some boards, timing seems to be important, and the later detection will fail.
286 ioTag_t motorIoTag = timerioTagGetByUsage(TIM_USE_MOTOR, 0);
288 if (motorIoTag) {
289 detectBrushedESC(motorIoTag);
291 #endif
293 enum {
294 FLASH_INIT_ATTEMPTED = (1 << 0),
295 SD_INIT_ATTEMPTED = (1 << 1),
296 SPI_AND_QSPI_INIT_ATTEMPTED = (1 << 2),
298 uint8_t initFlags = 0;
300 #ifdef CONFIG_IN_SDCARD
303 // Config in sdcard presents an issue with pin configuration since the pin and sdcard configs for the
304 // sdcard are in the config which is on the sdcard which we can't read yet!
306 // FIXME We need to add configuration somewhere, e.g. bootloader image or reserved flash area, that can be read by the firmware.
307 // it's currently possible for the firmware resource allocation to be wrong after the config is loaded if the user changes the settings.
308 // This would cause undefined behaviour once the config is loaded. so for now, users must NOT change sdio/spi configs needed for
309 // the system to boot and/or to save the config.
311 // note that target specific SDCARD/SDIO/SPI/QUADSPI configs are
312 // also not supported in USE_TARGET_CONFIG/targetConfigure() when using CONFIG_IN_SDCARD.
316 // IMPORTANT: all default flash and pin configurations must be valid for the target after pgResetAll() is called.
317 // Target designers must ensure other devices connected the same SPI/QUADSPI interface as the flash chip do not
318 // cause communication issues with the flash chip. e.g. use external pullups on SPI/QUADSPI CS lines.
321 #ifdef TARGET_BUS_INIT
322 #error "CONFIG_IN_SDCARD and TARGET_BUS_INIT are mutually exclusive"
323 #endif
325 pgResetAll();
327 #ifdef USE_SDCARD_SPI
328 configureSPIAndQuadSPI();
329 initFlags |= SPI_AND_QSPI_INIT_ATTEMPTED;
330 #endif
332 sdCardAndFSInit();
333 initFlags |= SD_INIT_ATTEMPTED;
335 if (!sdcard_isInserted()) {
336 failureMode(FAILURE_SDCARD_REQUIRED);
339 while (afatfs_getFilesystemState() != AFATFS_FILESYSTEM_STATE_READY) {
340 afatfs_poll();
342 if (afatfs_getFilesystemState() == AFATFS_FILESYSTEM_STATE_FATAL) {
343 failureMode(FAILURE_SDCARD_INITIALISATION_FAILED);
347 #endif // CONFIG_IN_SDCARD
349 #ifdef CONFIG_IN_EXTERNAL_FLASH
351 // Config on external flash presents an issue with pin configuration since the pin and flash configs for the
352 // external flash are in the config which is on a chip which we can't read yet!
354 // FIXME We need to add configuration somewhere, e.g. bootloader image or reserved flash area, that can be read by the firmware.
355 // it's currently possible for the firmware resource allocation to be wrong after the config is loaded if the user changes the settings.
356 // This would cause undefined behaviour once the config is loaded. so for now, users must NOT change flash/pin configs needed for
357 // the system to boot and/or to save the config.
359 // note that target specific FLASH/SPI/QUADSPI configs are
360 // also not supported in USE_TARGET_CONFIG/targetConfigure() when using CONFIG_IN_EXTERNAL_FLASH.
364 // IMPORTANT: all default flash and pin configurations must be valid for the target after pgResetAll() is called.
365 // Target designers must ensure other devices connected the same SPI/QUADSPI interface as the flash chip do not
366 // cause communication issues with the flash chip. e.g. use external pullups on SPI/QUADSPI CS lines.
368 pgResetAll();
370 #ifdef TARGET_BUS_INIT
371 #error "CONFIG_IN_EXTERNAL_FLASH and TARGET_BUS_INIT are mutually exclusive"
372 #endif
374 configureSPIAndQuadSPI();
375 initFlags |= SPI_AND_QSPI_INIT_ATTEMPTED;
378 #ifndef USE_FLASH_CHIP
379 #error "CONFIG_IN_EXTERNAL_FLASH requires USE_FLASH_CHIP to be defined."
380 #endif
382 bool haveFlash = flashInit(flashConfig());
384 if (!haveFlash) {
385 failureMode(FAILURE_EXTERNAL_FLASH_INIT_FAILED);
387 initFlags |= FLASH_INIT_ATTEMPTED;
389 #endif // CONFIG_IN_EXTERNAL_FLASH
391 initEEPROM();
393 ensureEEPROMStructureIsValid();
395 bool readSuccess = readEEPROM();
397 #if defined(USE_BOARD_INFO)
398 initBoardInformation();
399 #endif
401 if (!readSuccess || !isEEPROMVersionValid() || strncasecmp(systemConfig()->boardIdentifier, TARGET_BOARD_IDENTIFIER, sizeof(TARGET_BOARD_IDENTIFIER))) {
402 resetEEPROM(false);
405 systemState |= SYSTEM_STATE_CONFIG_LOADED;
407 #ifdef USE_DEBUG_PIN
408 dbgPinInit();
409 #endif
411 #ifdef USE_BRUSHED_ESC_AUTODETECT
412 // Now detect again with the actually configured pin for motor 1, if it is not the default pin.
413 ioTag_t configuredMotorIoTag = motorConfig()->dev.ioTags[0];
415 if (configuredMotorIoTag && configuredMotorIoTag != motorIoTag) {
416 detectBrushedESC(configuredMotorIoTag);
418 #endif
420 debugMode = systemConfig()->debug_mode;
422 #ifdef TARGET_PREINIT
423 targetPreInit();
424 #endif
426 #if !defined(USE_FAKE_LED)
427 ledInit(statusLedConfig());
428 #endif
429 LED2_ON;
431 #if !defined(SIMULATOR_BUILD)
432 EXTIInit();
433 #endif
435 #if defined(USE_BUTTONS)
437 buttonsInit();
439 delayMicroseconds(10); // allow configuration to settle // XXX Could be removed, too?
441 // Allow EEPROM reset with two-button-press without power cycling in DEBUG build
442 #ifdef DEBUG
443 #define EEPROM_RESET_PRECONDITION true
444 #else
445 #define EEPROM_RESET_PRECONDITION (!isMPUSoftReset())
446 #endif
448 if (EEPROM_RESET_PRECONDITION) {
449 #if defined(BUTTON_A_PIN) && defined(BUTTON_B_PIN)
450 // two buttons required
451 uint8_t secondsRemaining = 5;
452 bool bothButtonsHeld;
453 do {
454 bothButtonsHeld = buttonAPressed() && buttonBPressed();
455 if (bothButtonsHeld) {
456 if (--secondsRemaining == 0) {
457 resetEEPROM(false);
458 #ifdef USE_PERSISTENT_OBJECTS
459 persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_NONE);
460 #endif
461 systemReset();
463 delay(1000);
464 LED0_TOGGLE;
466 } while (bothButtonsHeld);
467 #endif
470 #undef EEPROM_RESET_PRECONDITION
472 #endif // USE_BUTTONS
474 // Note that spektrumBind checks if a call is immediately after
475 // hard reset (including power cycle), so it should be called before
476 // systemClockSetHSEValue and OverclockRebootIfNecessary, as these
477 // may cause soft reset which will prevent spektrumBind not to execute
478 // the bind procedure.
480 #if defined(USE_SPEKTRUM_BIND)
481 if (featureIsEnabled(FEATURE_RX_SERIAL)) {
482 switch (rxConfig()->serialrx_provider) {
483 case SERIALRX_SPEKTRUM1024:
484 case SERIALRX_SPEKTRUM2048:
485 case SERIALRX_SRXL:
486 // Spektrum satellite binding if enabled on startup.
487 // Must be called before that 100ms sleep so that we don't lose satellite's binding window after startup.
488 // The rest of Spektrum initialization will happen later - via spektrumInit()
489 spektrumBind(rxConfigMutable());
490 break;
493 #endif
495 #if defined(STM32F4) || defined(STM32G4)
496 // F4 has non-8MHz boards
497 // G4 for Betaflight allow 24 or 27MHz oscillator
498 systemClockSetHSEValue(systemConfig()->hseMhz * 1000000U);
499 #endif
501 #ifdef USE_OVERCLOCK
502 OverclockRebootIfNecessary(systemConfig()->cpu_overclock);
503 #endif
505 // Configure MCO output after config is stable
506 #ifdef USE_MCO
507 // Note that mcoConfigure must be augmented with an additional argument to
508 // indicate which device instance to configure when MCO and MCO2 are both supported
510 #if defined(STM32F4) || defined(STM32F7)
511 // F4 and F7 support MCO on PA8 and MCO2 on PC9, but only MCO2 is supported for now
512 mcoConfigure(MCODEV_2, mcoConfig(MCODEV_2));
513 #elif defined(STM32G4)
514 // G4 only supports one MCO on PA8
515 mcoConfigure(MCODEV_1, mcoConfig(MCODEV_1));
516 #else
517 #error Unsupported MCU
518 #endif
519 #endif // USE_MCO
521 #ifdef USE_TIMER
522 timerInit(); // timer must be initialized before any channel is allocated
523 #endif
525 #ifdef BUS_SWITCH_PIN
526 busSwitchInit();
527 #endif
529 #if defined(USE_UART) && !defined(SIMULATOR_BUILD)
530 uartPinConfigure(serialPinConfig());
531 #endif
533 #if defined(AVOID_UART1_FOR_PWM_PPM)
534 serialInit(featureIsEnabled(FEATURE_SOFTSERIAL),
535 featureIsEnabled(FEATURE_RX_PPM) || featureIsEnabled(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART1 : SERIAL_PORT_NONE);
536 #elif defined(AVOID_UART2_FOR_PWM_PPM)
537 serialInit(featureIsEnabled(FEATURE_SOFTSERIAL),
538 featureIsEnabled(FEATURE_RX_PPM) || featureIsEnabled(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART2 : SERIAL_PORT_NONE);
539 #elif defined(AVOID_UART3_FOR_PWM_PPM)
540 serialInit(featureIsEnabled(FEATURE_SOFTSERIAL),
541 featureIsEnabled(FEATURE_RX_PPM) || featureIsEnabled(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART3 : SERIAL_PORT_NONE);
542 #else
543 serialInit(featureIsEnabled(FEATURE_SOFTSERIAL), SERIAL_PORT_NONE);
544 #endif
546 mixerInit(mixerConfig()->mixerMode);
548 uint16_t idlePulse = motorConfig()->mincommand;
549 if (featureIsEnabled(FEATURE_3D)) {
550 idlePulse = flight3DConfig()->neutral3d;
552 if (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_BRUSHED) {
553 idlePulse = 0; // brushed motors
555 #ifdef USE_MOTOR
556 /* Motors needs to be initialized soon as posible because hardware initialization
557 * may send spurious pulses to esc's causing their early initialization. Also ppm
558 * receiver may share timer with motors so motors MUST be initialized here. */
559 motorDevInit(&motorConfig()->dev, idlePulse, getMotorCount());
560 systemState |= SYSTEM_STATE_MOTORS_READY;
561 #else
562 UNUSED(idlePulse);
563 #endif
565 if (0) {}
566 #if defined(USE_PPM)
567 else if (featureIsEnabled(FEATURE_RX_PPM)) {
568 ppmRxInit(ppmConfig());
570 #endif
571 #if defined(USE_PWM)
572 else if (featureIsEnabled(FEATURE_RX_PARALLEL_PWM)) {
573 pwmRxInit(pwmConfig());
575 #endif
577 #ifdef USE_BEEPER
578 beeperInit(beeperDevConfig());
579 #endif
580 /* temp until PGs are implemented. */
581 #if defined(USE_INVERTER) && !defined(SIMULATOR_BUILD)
582 initInverters(serialPinConfig());
583 #endif
586 #ifdef TARGET_BUS_INIT
587 targetBusInit();
589 #else
591 // Depending on compilation options SPI/QSPI initialisation may already be done.
592 if (!(initFlags & SPI_AND_QSPI_INIT_ATTEMPTED)) {
593 configureSPIAndQuadSPI();
594 initFlags |= SPI_AND_QSPI_INIT_ATTEMPTED;
597 #if defined(USE_SDCARD_SDIO) && !defined(CONFIG_IN_SDCARD) && defined(STM32H7)
598 sdioPinConfigure();
599 SDIO_GPIO_Init();
600 #endif
602 #ifdef USE_USB_MSC
603 /* MSC mode will start after init, but will not allow scheduler to run,
604 * so there is no bottleneck in reading and writing data */
605 mscInit();
606 if (mscCheckBootAndReset() || mscCheckButton()) {
607 ledInit(statusLedConfig());
609 #ifdef USE_SDCARD
610 if (blackboxConfig()->device == BLACKBOX_DEVICE_SDCARD) {
611 if (sdcardConfig()->mode) {
612 if (!(initFlags & SD_INIT_ATTEMPTED)) {
613 sdCardAndFSInit();
614 initFlags |= SD_INIT_ATTEMPTED;
618 #endif
620 #if defined(USE_FLASHFS)
621 // If the blackbox device is onboard flash, then initialize and scan
622 // it to identify the log files *before* starting the USB device to
623 // prevent timeouts of the mass storage device.
624 if (blackboxConfig()->device == BLACKBOX_DEVICE_FLASH) {
625 emfat_init_files();
627 #endif
628 // There's no more initialisation to be done, so enable DMA where possible for SPI
629 #ifdef USE_SPI
630 spiInitBusDMA();
631 #endif
632 if (mscStart() == 0) {
633 mscWaitForButton();
634 } else {
635 systemResetFromMsc();
638 #endif
640 #ifdef USE_PERSISTENT_MSC_RTC
641 // if we didn't enter MSC mode then clear the persistent RTC value
642 persistentObjectWrite(PERSISTENT_OBJECT_RTC_HIGH, 0);
643 persistentObjectWrite(PERSISTENT_OBJECT_RTC_LOW, 0);
644 #endif
646 #ifdef USE_I2C
647 i2cHardwareConfigure(i2cConfig(0));
649 // Note: Unlike UARTs which are configured when client is present,
650 // I2C buses are initialized unconditionally if they are configured.
652 #ifdef USE_I2C_DEVICE_1
653 i2cInit(I2CDEV_1);
654 #endif
655 #ifdef USE_I2C_DEVICE_2
656 i2cInit(I2CDEV_2);
657 #endif
658 #ifdef USE_I2C_DEVICE_3
659 i2cInit(I2CDEV_3);
660 #endif
661 #ifdef USE_I2C_DEVICE_4
662 i2cInit(I2CDEV_4);
663 #endif
664 #endif // USE_I2C
666 #endif // TARGET_BUS_INIT
668 #ifdef USE_HARDWARE_REVISION_DETECTION
669 updateHardwareRevision();
670 #endif
672 #ifdef USE_VTX_RTC6705
673 bool useRTC6705 = rtc6705IOInit(vtxIOConfig());
674 #endif
676 #ifdef USE_CAMERA_CONTROL
677 cameraControlInit();
678 #endif
680 #ifdef USE_ADC
681 adcInit(adcConfig());
682 #endif
684 initBoardAlignment(boardAlignment());
686 if (!sensorsAutodetect()) {
687 // if gyro was not detected due to whatever reason, notify and don't arm.
688 if (isSystemConfigured()) {
689 indicateFailure(FAILURE_MISSING_ACC, 2);
691 setArmingDisabled(ARMING_DISABLED_NO_GYRO);
694 systemState |= SYSTEM_STATE_SENSORS_READY;
696 // Set the targetLooptime based on the detected gyro sampleRateHz and pid_process_denom
697 gyroSetTargetLooptime(pidConfig()->pid_process_denom);
699 // Validate and correct the gyro config or PID loop time if needed
700 validateAndFixGyroConfig();
702 // Now reset the targetLooptime as it's possible for the validation to change the pid_process_denom
703 gyroSetTargetLooptime(pidConfig()->pid_process_denom);
705 // Finally initialize the gyro filtering
706 gyroInitFilters();
708 pidInit(currentPidProfile);
710 mixerInitProfile();
712 #ifdef USE_PID_AUDIO
713 pidAudioInit();
714 #endif
716 #ifdef USE_SERVOS
717 servosInit();
718 if (isMixerUsingServos()) {
719 //pwm_params.useChannelForwarding = featureIsEnabled(FEATURE_CHANNEL_FORWARDING);
720 servoDevInit(&servoConfig()->dev);
722 servosFilterInit();
723 #endif
725 #ifdef USE_PINIO
726 pinioInit(pinioConfig());
727 #endif
729 #ifdef USE_PIN_PULL_UP_DOWN
730 pinPullupPulldownInit();
731 #endif
733 #ifdef USE_PINIOBOX
734 pinioBoxInit(pinioBoxConfig());
735 #endif
737 LED1_ON;
738 LED0_OFF;
739 LED2_OFF;
741 for (int i = 0; i < 10; i++) {
742 LED1_TOGGLE;
743 LED0_TOGGLE;
744 #if defined(USE_BEEPER)
745 delay(25);
746 if (!(beeperConfig()->beeper_off_flags & BEEPER_GET_FLAG(BEEPER_SYSTEM_INIT))) {
747 BEEP_ON;
749 delay(25);
750 BEEP_OFF;
751 #else
752 delay(50);
753 #endif
755 LED0_OFF;
756 LED1_OFF;
758 imuInit();
760 failsafeInit();
762 rxInit();
764 #ifdef USE_GPS
765 if (featureIsEnabled(FEATURE_GPS)) {
766 gpsInit();
767 #ifdef USE_GPS_RESCUE
768 gpsRescueInit();
769 #endif
771 #endif
773 #ifdef USE_LED_STRIP
774 ledStripInit();
776 if (featureIsEnabled(FEATURE_LED_STRIP)) {
777 ledStripEnable();
779 #endif
781 #ifdef USE_ESC_SENSOR
782 if (featureIsEnabled(FEATURE_ESC_SENSOR)) {
783 escSensorInit();
785 #endif
787 #ifdef USE_USB_DETECT
788 usbCableDetectInit();
789 #endif
791 #ifdef USE_TRANSPONDER
792 if (featureIsEnabled(FEATURE_TRANSPONDER)) {
793 transponderInit();
794 transponderStartRepeating();
795 systemState |= SYSTEM_STATE_TRANSPONDER_ENABLED;
797 #endif
799 #ifdef USE_FLASH_CHIP
800 if (!(initFlags & FLASH_INIT_ATTEMPTED)) {
801 flashInit(flashConfig());
802 initFlags |= FLASH_INIT_ATTEMPTED;
804 #endif
805 #ifdef USE_FLASHFS
806 flashfsInit();
807 #endif
809 #ifdef USE_BLACKBOX
810 #ifdef USE_SDCARD
811 if (blackboxConfig()->device == BLACKBOX_DEVICE_SDCARD) {
812 if (sdcardConfig()->mode) {
813 if (!(initFlags & SD_INIT_ATTEMPTED)) {
814 sdCardAndFSInit();
815 initFlags |= SD_INIT_ATTEMPTED;
819 #endif
820 blackboxInit();
821 #endif
823 #ifdef USE_ACC
824 if (mixerConfig()->mixerMode == MIXER_GIMBAL) {
825 accStartCalibration();
827 #endif
828 gyroStartCalibration(false);
829 #ifdef USE_BARO
830 baroStartCalibration();
831 #endif
832 positionInit();
834 #if defined(USE_VTX_COMMON) || defined(USE_VTX_CONTROL)
835 vtxTableInit();
836 #endif
838 #ifdef USE_VTX_CONTROL
839 vtxControlInit();
841 #if defined(USE_VTX_COMMON)
842 vtxCommonInit();
843 #endif
845 #ifdef USE_VTX_MSP
846 vtxMspInit();
847 #endif
849 #ifdef USE_VTX_SMARTAUDIO
850 vtxSmartAudioInit();
851 #endif
853 #ifdef USE_VTX_TRAMP
854 vtxTrampInit();
855 #endif
857 #ifdef USE_VTX_RTC6705
858 if (!vtxCommonDevice() && useRTC6705) { // external VTX takes precedence when configured.
859 vtxRTC6705Init();
861 #endif
863 #endif // VTX_CONTROL
865 #ifdef USE_TIMER
866 // start all timers
867 // TODO - not implemented yet
868 timerStart();
869 #endif
871 batteryInit(); // always needs doing, regardless of features.
873 #ifdef USE_RCDEVICE
874 rcdeviceInit();
875 #endif // USE_RCDEVICE
877 #ifdef USE_PERSISTENT_STATS
878 statsInit();
879 #endif
881 // Initialize MSP
882 mspInit();
883 mspSerialInit();
886 * CMS, display devices and OSD
888 #ifdef USE_CMS
889 cmsInit();
890 #endif
892 #if (defined(USE_OSD) || (defined(USE_MSP_DISPLAYPORT) && defined(USE_CMS)))
893 displayPort_t *osdDisplayPort = NULL;
894 #endif
896 #if defined(USE_OSD)
897 osdDisplayPortDevice_e osdDisplayPortDevice = OSD_DISPLAYPORT_DEVICE_NONE;
899 //The OSD need to be initialised after GYRO to avoid GYRO initialisation failure on some targets
901 if (featureIsEnabled(FEATURE_OSD)) {
902 osdDisplayPortDevice_e device = osdConfig()->displayPortDevice;
904 switch(device) {
906 case OSD_DISPLAYPORT_DEVICE_AUTO:
907 FALLTHROUGH;
909 #if defined(USE_FRSKYOSD)
910 // Test OSD_DISPLAYPORT_DEVICE_FRSKYOSD first, since an FC could
911 // have a builtin MAX7456 but also an FRSKYOSD connected to an
912 // uart.
913 case OSD_DISPLAYPORT_DEVICE_FRSKYOSD:
914 osdDisplayPort = frskyOsdDisplayPortInit(vcdProfile()->video_system);
915 if (osdDisplayPort || device == OSD_DISPLAYPORT_DEVICE_FRSKYOSD) {
916 osdDisplayPortDevice = OSD_DISPLAYPORT_DEVICE_FRSKYOSD;
917 break;
919 FALLTHROUGH;
920 #endif
922 #if defined(USE_MAX7456)
923 case OSD_DISPLAYPORT_DEVICE_MAX7456:
924 // If there is a max7456 chip for the OSD configured and detected then use it.
925 if (max7456DisplayPortInit(vcdProfile(), &osdDisplayPort) || device == OSD_DISPLAYPORT_DEVICE_MAX7456) {
926 osdDisplayPortDevice = OSD_DISPLAYPORT_DEVICE_MAX7456;
927 break;
929 FALLTHROUGH;
930 #endif
932 #if defined(USE_CMS) && defined(USE_MSP_DISPLAYPORT) && defined(USE_OSD_OVER_MSP_DISPLAYPORT)
933 case OSD_DISPLAYPORT_DEVICE_MSP:
934 osdDisplayPort = displayPortMspInit();
935 if (osdDisplayPort || device == OSD_DISPLAYPORT_DEVICE_MSP) {
936 osdDisplayPortDevice = OSD_DISPLAYPORT_DEVICE_MSP;
937 break;
939 FALLTHROUGH;
940 #endif
942 // Other device cases can be added here
944 case OSD_DISPLAYPORT_DEVICE_NONE:
945 default:
946 break;
949 // osdInit will register with CMS by itself.
950 osdInit(osdDisplayPort, osdDisplayPortDevice);
952 if (osdDisplayPortDevice == OSD_DISPLAYPORT_DEVICE_NONE) {
953 featureDisableImmediate(FEATURE_OSD);
956 #endif // USE_OSD
958 #if defined(USE_CMS) && defined(USE_MSP_DISPLAYPORT)
959 // If BFOSD is not active, then register MSP_DISPLAYPORT as a CMS device.
960 if (!osdDisplayPort) {
961 cmsDisplayPortRegister(displayPortMspInit());
963 #endif
965 #ifdef USE_DASHBOARD
966 // Dashbord will register with CMS by itself.
967 if (featureIsEnabled(FEATURE_DASHBOARD)) {
968 dashboardInit();
969 #ifdef USE_OLED_GPS_DEBUG_PAGE_ONLY
970 dashboardShowFixedPage(PAGE_GPS);
971 #else
972 dashboardResetPageCycling();
973 dashboardEnablePageCycling();
974 #endif
976 #endif
978 #ifdef USE_TELEMETRY
979 // Telemetry will initialise displayport and register with CMS by itself.
980 if (featureIsEnabled(FEATURE_TELEMETRY)) {
981 telemetryInit();
983 #endif
985 setArmingDisabled(ARMING_DISABLED_BOOT_GRACE_TIME);
987 // On F4/F7 allocate SPI DMA streams before motor timers
988 #if defined(STM32F4) || defined(STM32F7)
989 #ifdef USE_SPI
990 // Attempt to enable DMA on all SPI busses
991 spiInitBusDMA();
992 #endif
993 #endif
995 #ifdef USE_MOTOR
996 motorPostInit();
997 motorEnable();
998 #endif
1000 // On H7/G4 allocate SPI DMA streams after motor timers as SPI DMA allocate will always be possible
1001 #if defined(STM32H7) || defined(STM32G4)
1002 #ifdef USE_SPI
1003 // Attempt to enable DMA on all SPI busses
1004 spiInitBusDMA();
1005 #endif
1006 #endif
1008 swdPinsInit();
1010 unusedPinsInit();
1012 tasksInit();
1014 systemState |= SYSTEM_STATE_READY;