Fix WS2812 led definition
[inav.git] / src / main / fc / fc_init.c
bloba8ab8146d2f4a352231ede414f5a5c3982f0a626
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>
22 #include "platform.h"
24 #include "blackbox/blackbox.h"
25 #include "blackbox/blackbox_io.h"
27 #include "build/assert.h"
28 #include "build/atomic.h"
29 #include "build/build_config.h"
30 #include "build/debug.h"
32 #include "common/axis.h"
33 #include "common/color.h"
34 #include "common/log.h"
35 #include "common/maths.h"
36 #include "common/memory.h"
37 #include "common/printf.h"
38 #include "programming/global_variables.h"
40 #include "config/config_eeprom.h"
41 #include "config/feature.h"
42 #include "config/parameter_group.h"
43 #include "config/parameter_group_ids.h"
45 #include "cms/cms.h"
47 #include "drivers/1-wire.h"
48 #include "drivers/accgyro/accgyro.h"
49 #include "drivers/adc.h"
50 #include "drivers/compass/compass.h"
51 #include "drivers/bus.h"
52 #include "drivers/dma.h"
53 #include "drivers/exti.h"
54 #include "drivers/io.h"
55 #include "drivers/flash.h"
56 #include "drivers/light_led.h"
57 #include "drivers/nvic.h"
58 #include "drivers/osd.h"
59 #include "drivers/persistent.h"
60 #include "drivers/pwm_esc_detect.h"
61 #include "drivers/pwm_mapping.h"
62 #include "drivers/pwm_output.h"
63 #include "drivers/pwm_output.h"
64 #include "drivers/sensor.h"
65 #include "drivers/serial.h"
66 #include "drivers/serial_softserial.h"
67 #include "drivers/serial_uart.h"
68 #include "drivers/serial_usb_vcp.h"
69 #include "drivers/sound_beeper.h"
70 #include "drivers/system.h"
71 #include "drivers/time.h"
72 #include "drivers/timer.h"
73 #include "drivers/uart_inverter.h"
74 #include "drivers/io.h"
75 #include "drivers/vtx_common.h"
76 #ifdef USE_USB_MSC
77 #include "drivers/usb_msc.h"
78 #include "msc/emfat_file.h"
79 #endif
80 #include "drivers/sdcard/sdcard.h"
81 #include "drivers/sdio.h"
82 #include "drivers/io_port_expander.h"
84 #include "fc/cli.h"
85 #include "fc/config.h"
86 #include "fc/fc_msp.h"
87 #include "fc/fc_tasks.h"
88 #include "fc/rc_controls.h"
89 #include "fc/runtime_config.h"
90 #include "fc/firmware_update.h"
92 #include "flight/failsafe.h"
93 #include "flight/imu.h"
94 #include "flight/mixer.h"
95 #include "flight/pid.h"
96 #include "flight/power_limits.h"
97 #include "flight/rpm_filter.h"
98 #include "flight/servos.h"
100 #include "io/asyncfatfs/asyncfatfs.h"
101 #include "io/beeper.h"
102 #include "io/lights.h"
103 #include "io/dashboard.h"
104 #include "io/displayport_frsky_osd.h"
105 #include "io/displayport_msp.h"
106 #include "io/displayport_max7456.h"
107 #include "io/displayport_msp_osd.h"
108 #include "io/displayport_srxl.h"
109 #include "io/flashfs.h"
110 #include "io/gps.h"
111 #include "io/ledstrip.h"
112 #include "io/osd.h"
113 #include "io/osd_dji_hd.h"
114 #include "io/rcdevice_cam.h"
115 #include "io/serial.h"
116 #include "io/displayport_msp.h"
117 #include "io/smartport_master.h"
118 #include "io/vtx.h"
119 #include "io/vtx_control.h"
120 #include "io/vtx_smartaudio.h"
121 #include "io/vtx_tramp.h"
122 #include "io/vtx_ffpv24g.h"
123 #include "io/piniobox.h"
125 #include "msp/msp_serial.h"
127 #include "navigation/navigation.h"
129 #include "rx/rx.h"
130 #include "rx/spektrum.h"
132 #include "sensors/acceleration.h"
133 #include "sensors/barometer.h"
134 #include "sensors/battery.h"
135 #include "sensors/boardalignment.h"
136 #include "sensors/compass.h"
137 #include "sensors/gyro.h"
138 #include "sensors/initialisation.h"
139 #include "sensors/pitotmeter.h"
140 #include "sensors/rangefinder.h"
141 #include "sensors/sensors.h"
142 #include "sensors/esc_sensor.h"
144 #include "scheduler/scheduler.h"
146 #include "telemetry/telemetry.h"
148 #ifdef USE_HARDWARE_REVISION_DETECTION
149 #include "hardware_revision.h"
150 #endif
152 #ifdef USE_HARDWARE_PREBOOT_SETUP
153 extern void initialisePreBootHardware(void);
154 #endif
156 extern uint8_t motorControlEnable;
158 typedef enum {
159 SYSTEM_STATE_INITIALISING = 0,
160 SYSTEM_STATE_CONFIG_LOADED = (1 << 0),
161 SYSTEM_STATE_SENSORS_READY = (1 << 1),
162 SYSTEM_STATE_MOTORS_READY = (1 << 2),
163 SYSTEM_STATE_TRANSPONDER_ENABLED = (1 << 3),
164 SYSTEM_STATE_READY = (1 << 7)
165 } systemState_e;
167 uint8_t systemState = SYSTEM_STATE_INITIALISING;
169 void flashLedsAndBeep(void)
171 LED1_ON;
172 LED0_OFF;
173 for (uint8_t i = 0; i < 10; i++) {
174 LED1_TOGGLE;
175 LED0_TOGGLE;
176 delay(25);
177 if (!(getPreferredBeeperOffMask() & (1 << (BEEPER_SYSTEM_INIT - 1))))
178 BEEP_ON;
179 delay(25);
180 BEEP_OFF;
182 LED0_OFF;
183 LED1_OFF;
186 void init(void)
188 #if defined(USE_FLASHFS)
189 bool flashDeviceInitialized = false;
190 #endif
192 #ifdef USE_HAL_DRIVER
193 HAL_Init();
194 #endif
196 systemState = SYSTEM_STATE_INITIALISING;
197 printfSupportInit();
199 // Initialize system and CPU clocks to their initial values
200 systemInit();
202 __enable_irq();
204 // initialize IO (needed for all IO operations)
205 IOInitGlobal();
207 #ifdef USE_HARDWARE_REVISION_DETECTION
208 detectHardwareRevision();
209 #endif
211 #ifdef USE_BRUSHED_ESC_AUTODETECT
212 detectBrushedESC();
213 #endif
215 #ifdef CONFIG_IN_EXTERNAL_FLASH
216 // Reset config to defaults. Note: Default flash config must be functional for config in external flash to work.
217 pgResetAll(0);
219 flashDeviceInitialized = flashInit();
220 #endif
222 initEEPROM();
223 ensureEEPROMContainsValidData();
224 readEEPROM();
226 #ifdef USE_UNDERCLOCK
227 // Re-initialize system clock to their final values (if necessary)
228 systemClockSetup(systemConfig()->cpuUnderclock);
229 #else
230 systemClockSetup(false);
231 #endif
233 #ifdef USE_I2C
234 i2cSetSpeed(systemConfig()->i2c_speed);
235 #endif
237 #ifdef USE_HARDWARE_PREBOOT_SETUP
238 initialisePreBootHardware();
239 #endif
241 systemState |= SYSTEM_STATE_CONFIG_LOADED;
243 debugMode = systemConfig()->debug_mode;
245 // Latch active features to be used for feature() in the remainder of init().
246 latchActiveFeatures();
248 ledInit(false);
250 EXTIInit();
252 #ifdef USE_SPEKTRUM_BIND
253 if (rxConfig()->receiverType == RX_TYPE_SERIAL) {
254 switch (rxConfig()->serialrx_provider) {
255 case SERIALRX_SPEKTRUM1024:
256 case SERIALRX_SPEKTRUM2048:
257 // Spektrum satellite binding if enabled on startup.
258 // Must be called before that 100ms sleep so that we don't lose satellite's binding window after startup.
259 // The rest of Spektrum initialization will happen later - via spektrumInit()
260 spektrumBind(rxConfigMutable());
261 break;
264 #endif
266 #ifdef USE_VCP
267 // Early initialize USB hardware
268 usbVcpInitHardware();
269 #endif
271 timerInit(); // timer must be initialized before any channel is allocated
273 serialInit(feature(FEATURE_SOFTSERIAL));
275 // Initialize MSP serial ports here so LOG can share a port with MSP.
276 // XXX: Don't call mspFcInit() yet, since it initializes the boxes and needs
277 // to run after the sensors have been detected.
278 mspSerialInit();
280 #if defined(USE_DJI_HD_OSD)
281 // DJI OSD uses a special flavour of MSP (subset of Betaflight 4.1.1 MSP) - process as part of serial task
282 djiOsdSerialInit();
283 #endif
285 #if defined(USE_SMARTPORT_MASTER)
286 smartportMasterInit();
287 #endif
289 #if defined(USE_LOG)
290 // LOG might use serial output, so we only can init it after serial port is ready
291 // From this point on we can use LOG_*() to produce real-time debugging information
292 logInit();
293 #endif
295 #ifdef USE_PROGRAMMING_FRAMEWORK
296 gvInit();
297 #endif
299 // Initialize servo and motor mixers
300 // This needs to be called early to set up platform type correctly and count required motors & servos
301 servosInit();
302 mixerUpdateStateFlags();
303 mixerInit();
305 // Some sanity checking
306 if (motorConfig()->motorPwmProtocol == PWM_TYPE_BRUSHED) {
307 featureClear(FEATURE_REVERSIBLE_MOTORS);
309 if (!STATE(ALTITUDE_CONTROL)) {
310 featureClear(FEATURE_AIRMODE);
313 // Initialize motor and servo outpus
314 if (pwmMotorAndServoInit()) {
315 DISABLE_ARMING_FLAG(ARMING_DISABLED_PWM_OUTPUT_ERROR);
317 else {
318 ENABLE_ARMING_FLAG(ARMING_DISABLED_PWM_OUTPUT_ERROR);
321 systemState |= SYSTEM_STATE_MOTORS_READY;
323 #ifdef USE_ESC_SENSOR
324 // DSHOT supports a dedicated wire ESC telemetry. Kick off the ESC-sensor receiver initialization
325 // We may, however, do listen_only, so need to init this anyway
326 // Initialize escSensor after having done it with outputs
327 escSensorInitialize();
328 #endif
330 #ifdef BEEPER
331 beeperDevConfig_t beeperDevConfig = {
332 .ioTag = IO_TAG(BEEPER),
333 #ifdef BEEPER_INVERTED
334 .isOD = false,
335 .isInverted = true
336 #else
337 .isOD = true,
338 .isInverted = false
339 #endif
342 beeperInit(&beeperDevConfig);
343 #endif
344 #ifdef USE_LIGHTS
345 lightsInit();
346 #endif
348 #ifdef USE_UART_INVERTER
349 uartInverterInit();
350 #endif
352 // Initialize buses
353 busInit();
355 #ifdef CONFIG_IN_EXTERNAL_FLASH
356 // busInit re-configures the SPI pins. Init flash again so it is ready to write settings
357 flashDeviceInitialized = flashInit();
358 #endif
360 #ifdef USE_HARDWARE_REVISION_DETECTION
361 updateHardwareRevision();
362 #endif
364 #if defined(USE_SDCARD_SDIO) && defined(STM32H7)
365 sdioPinConfigure();
366 SDIO_GPIO_Init();
367 #endif
369 #ifdef USE_USB_MSC
370 /* MSC mode will start after init, but will not allow scheduler to run,
371 * so there is no bottleneck in reading and writing data
373 mscInit();
374 #if defined(USE_FLASHFS)
375 // If the blackbox device is onboard flash, then initialize and scan
376 // it to identify the log files *before* starting the USB device to
377 // prevent timeouts of the mass storage device.
378 if (blackboxConfig()->device == BLACKBOX_DEVICE_FLASH) {
379 // Must initialise the device to read _anything_
380 if (!flashDeviceInitialized) {
381 flashDeviceInitialized = flashInit();
383 emfat_init_files();
385 #endif
387 if (mscCheckBoot() || mscCheckButton()) {
388 if (mscStart() == 0) {
389 mscWaitForButton();
390 } else {
391 NVIC_SystemReset();
394 #endif
396 #ifdef USE_I2C
397 #ifdef USE_I2C_DEVICE_1
398 #ifdef I2C_DEVICE_1_SHARES_UART3
399 if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {
400 i2cInit(I2CDEV_1);
402 #else
403 i2cInit(I2CDEV_1);
404 #endif
405 #endif
407 #ifdef USE_I2C_DEVICE_2
408 #ifdef I2C_DEVICE_2_SHARES_UART3
409 if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {
410 i2cInit(I2CDEV_2);
412 #else
413 i2cInit(I2CDEV_2);
414 #endif
415 #endif
417 #ifdef USE_I2C_DEVICE_3
418 i2cInit(I2CDEV_3);
419 #endif
421 #ifdef USE_I2C_DEVICE_4
422 i2cInit(I2CDEV_4);
423 #endif
425 #ifdef USE_I2C_DEVICE_EMULATED
426 #ifdef I2C_DEVICE_EMULATED_SHARES_UART3
427 if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {
428 i2cInit(I2CDEV_EMULATED);
430 #else
431 i2cInit(I2CDEV_EMULATED);
432 #endif
433 #endif
434 #endif
436 #ifdef USE_ADC
437 drv_adc_config_t adc_params;
438 memset(&adc_params, 0, sizeof(adc_params));
440 // Allocate and initialize ADC channels if features are configured - can't rely on sensor detection here, it's done later
441 if (feature(FEATURE_VBAT)) {
442 adc_params.adcFunctionChannel[ADC_BATTERY] = adcChannelConfig()->adcFunctionChannel[ADC_BATTERY];
445 if (feature(FEATURE_RSSI_ADC)) {
446 adc_params.adcFunctionChannel[ADC_RSSI] = adcChannelConfig()->adcFunctionChannel[ADC_RSSI];
449 if (feature(FEATURE_CURRENT_METER) && batteryMetersConfig()->current.type == CURRENT_SENSOR_ADC) {
450 adc_params.adcFunctionChannel[ADC_CURRENT] = adcChannelConfig()->adcFunctionChannel[ADC_CURRENT];
453 #if defined(USE_PITOT) && defined(USE_ADC) && defined(USE_PITOT_ADC)
454 if (pitotmeterConfig()->pitot_hardware == PITOT_ADC || pitotmeterConfig()->pitot_hardware == PITOT_AUTODETECT) {
455 adc_params.adcFunctionChannel[ADC_AIRSPEED] = adcChannelConfig()->adcFunctionChannel[ADC_AIRSPEED];
457 #endif
459 adcInit(&adc_params);
460 #endif
462 #ifdef USE_PINIO
463 pinioInit();
464 #endif
466 #ifdef USE_PINIOBOX
467 pinioBoxInit();
468 #endif
470 #if defined(USE_GPS) || defined(USE_MAG)
471 delay(500);
473 /* Extra 500ms delay prior to initialising hardware if board is cold-booting */
474 if (!isMPUSoftReset()) {
475 LED1_ON;
476 LED0_OFF;
478 for (int i = 0; i < 5; i++) {
479 LED1_TOGGLE;
480 LED0_TOGGLE;
481 delay(100);
484 LED0_OFF;
485 LED1_OFF;
487 #endif
489 initBoardAlignment();
491 #ifdef USE_CMS
492 cmsInit();
493 #endif
495 #ifdef USE_DASHBOARD
496 if (feature(FEATURE_DASHBOARD)) {
497 dashboardInit();
499 #endif
501 #ifdef USE_GPS
502 if (feature(FEATURE_GPS)) {
503 gpsPreInit();
505 #endif
507 // 1-Wire IF chip
508 #ifdef USE_1WIRE
509 owInit();
510 #endif
512 if (!sensorsAutodetect()) {
513 // if gyro was not detected due to whatever reason, we give up now.
514 failureMode(FAILURE_MISSING_ACC);
517 systemState |= SYSTEM_STATE_SENSORS_READY;
519 flashLedsAndBeep();
521 pidInitFilters();
523 imuInit();
525 // Sensors have now been detected, mspFcInit() can now be called
526 // to set the boxes up
527 mspFcInit();
529 cliInit(serialConfig());
531 failsafeInit();
533 rxInit();
535 #if defined(USE_OSD)
536 displayPort_t *osdDisplayPort = NULL;
537 #endif
539 #ifdef USE_OSD
540 if (feature(FEATURE_OSD)) {
541 #if defined(USE_FRSKYOSD)
542 if (!osdDisplayPort) {
543 osdDisplayPort = frskyOSDDisplayPortInit(osdConfig()->video_system);
545 #endif
546 #ifdef USE_MSP_OSD
547 if (!osdDisplayPort) {
548 osdDisplayPort = mspOsdDisplayPortInit(osdConfig()->video_system);
550 #endif
551 #if defined(USE_MAX7456)
552 // If there is a max7456 chip for the OSD and we have no
553 // external OSD initialized, use it.
554 if (!osdDisplayPort) {
555 osdDisplayPort = max7456DisplayPortInit(osdConfig()->video_system);
557 #elif defined(USE_OSD_OVER_MSP_DISPLAYPORT) // OSD over MSP; not supported (yet)
558 if (!osdDisplayPort) {
559 osdDisplayPort = displayPortMspInit();
561 #endif
562 // osdInit will register with CMS by itself.
563 osdInit(osdDisplayPort);
565 #endif
567 #if defined(USE_CMS) && defined(USE_SPEKTRUM_CMS_TELEMETRY) && defined(USE_TELEMETRY_SRXL)
568 // Register the srxl Textgen telemetry sensor as a displayport device
569 cmsDisplayPortRegister(displayPortSrxlInit());
570 #endif
572 #ifdef USE_GPS
573 if (feature(FEATURE_GPS)) {
574 gpsInit();
576 #endif
579 navigationInit();
581 #ifdef USE_LED_STRIP
582 ledStripInit();
584 if (feature(FEATURE_LED_STRIP)) {
585 ledStripEnable();
587 #endif
589 #ifdef USE_TELEMETRY
590 if (feature(FEATURE_TELEMETRY)) {
591 telemetryInit();
593 #endif
595 #ifdef USE_BLACKBOX
597 //Do not allow blackbox to be run faster that 1kHz. It can cause UAV to drop dead when digital ESC protocol is used
598 const uint32_t blackboxLooptime = getLooptime() * blackboxConfig()->rate_denom / blackboxConfig()->rate_num;
600 if (blackboxLooptime < 1000) {
601 blackboxConfigMutable()->rate_num = 1;
602 blackboxConfigMutable()->rate_denom = ceil(1000 / getLooptime());
605 // SDCARD and FLASHFS are used only for blackbox
606 // Make sure we only init what's necessary for blackbox
607 switch (blackboxConfig()->device) {
608 #ifdef USE_FLASHFS
609 case BLACKBOX_DEVICE_FLASH:
610 if (!flashDeviceInitialized) {
611 flashDeviceInitialized = flashInit();
613 if (flashDeviceInitialized) {
614 // do not initialize flashfs if no flash was found
615 flashfsInit();
617 break;
618 #endif
620 #ifdef USE_SDCARD
621 case BLACKBOX_DEVICE_SDCARD:
622 sdcardInsertionDetectInit();
623 sdcard_init();
624 afatfs_init();
625 break;
626 #endif
627 default:
628 break;
631 blackboxInit();
632 #endif
634 gyroStartCalibration();
636 #ifdef USE_BARO
637 baroStartCalibration();
638 #endif
640 #ifdef USE_PITOT
641 pitotStartCalibration();
642 #endif
644 #if defined(USE_VTX_CONTROL)
645 vtxControlInit();
646 vtxCommonInit();
647 vtxInit();
649 #ifdef USE_VTX_SMARTAUDIO
650 vtxSmartAudioInit();
651 #endif
653 #ifdef USE_VTX_TRAMP
654 vtxTrampInit();
655 #endif
657 #ifdef USE_VTX_FFPV
658 vtxFuriousFPVInit();
659 #endif
661 #endif // USE_VTX_CONTROL
663 // Now that everything has powered up the voltage and cell count be determined.
664 if (feature(FEATURE_VBAT | FEATURE_CURRENT_METER))
665 batteryInit();
667 #ifdef USE_RCDEVICE
668 rcdeviceInit();
669 #endif // USE_RCDEVICE
671 #ifdef USE_DSHOT
672 initDShotCommands();
673 #endif
675 // Latch active features AGAIN since some may be modified by init().
676 latchActiveFeatures();
677 motorControlEnable = true;
679 fcTasksInit();
681 #ifdef USE_OSD
682 if (feature(FEATURE_OSD) && (osdDisplayPort != NULL)) {
683 setTaskEnabled(TASK_OSD, feature(FEATURE_OSD));
685 #endif
687 #ifdef USE_RPM_FILTER
688 disableRpmFilters();
689 if (STATE(ESC_SENSOR_ENABLED) && (rpmFilterConfig()->gyro_filter_enabled || rpmFilterConfig()->dterm_filter_enabled)) {
690 rpmFiltersInit();
691 setTaskEnabled(TASK_RPM_FILTER, true);
693 #endif
695 #ifdef USE_I2C_IO_EXPANDER
696 ioPortExpanderInit();
697 #endif
699 #ifdef USE_POWER_LIMITS
700 powerLimiterInit();
701 #endif
703 // Considering that the persistent reset reason is only used during init
704 persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_NONE);
706 systemState |= SYSTEM_STATE_READY;