Added common target header file.
[betaflight.git] / src / main / main.c
blob320bd5ada838c6f22ccc25c2add9855cbfa7cab2
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 <stdlib.h>
21 #include <string.h>
23 #include "platform.h"
25 #include "scheduler/scheduler.h"
27 #include "common/axis.h"
28 #include "common/color.h"
29 #include "common/atomic.h"
30 #include "common/maths.h"
32 #include "drivers/nvic.h"
34 #include "drivers/sensor.h"
35 #include "drivers/system.h"
36 #include "drivers/gpio.h"
37 #include "drivers/light_led.h"
38 #include "drivers/sound_beeper.h"
39 #include "drivers/timer.h"
40 #include "drivers/serial.h"
41 #include "drivers/serial_softserial.h"
42 #include "drivers/serial_uart.h"
43 #include "drivers/accgyro.h"
44 #include "drivers/compass.h"
45 #include "drivers/pwm_mapping.h"
46 #include "drivers/pwm_rx.h"
47 #include "drivers/adc.h"
48 #include "drivers/bus_i2c.h"
49 #include "drivers/bus_spi.h"
50 #include "drivers/inverter.h"
51 #include "drivers/flash_m25p16.h"
52 #include "drivers/sonar_hcsr04.h"
53 #include "drivers/gyro_sync.h"
55 #include "rx/rx.h"
57 #include "io/beeper.h"
58 #include "io/serial.h"
59 #include "io/flashfs.h"
60 #include "io/gps.h"
61 #include "io/escservo.h"
62 #include "io/rc_controls.h"
63 #include "io/gimbal.h"
64 #include "io/ledstrip.h"
65 #include "io/display.h"
67 #include "sensors/sensors.h"
68 #include "sensors/sonar.h"
69 #include "sensors/barometer.h"
70 #include "sensors/compass.h"
71 #include "sensors/acceleration.h"
72 #include "sensors/gyro.h"
73 #include "sensors/battery.h"
74 #include "sensors/boardalignment.h"
75 #include "sensors/initialisation.h"
77 #include "telemetry/telemetry.h"
78 #include "blackbox/blackbox.h"
80 #include "flight/pid.h"
81 #include "flight/imu.h"
82 #include "flight/mixer.h"
83 #include "flight/failsafe.h"
84 #include "flight/navigation_rewrite.h"
86 #include "config/runtime_config.h"
87 #include "config/config.h"
88 #include "config/config_profile.h"
89 #include "config/config_master.h"
91 #ifdef USE_HARDWARE_REVISION_DETECTION
92 #include "hardware_revision.h"
93 #endif
95 #include "build_config.h"
96 #include "debug.h"
98 extern uint8_t motorControlEnable;
100 #ifdef SOFTSERIAL_LOOPBACK
101 serialPort_t *loopbackPort;
102 #endif
104 void printfSupportInit(void);
105 void timerInit(void);
106 void telemetryInit(void);
107 void serialInit(serialConfig_t *initialSerialConfig, bool softserialEnabled);
108 void mspInit();
109 void cliInit(serialConfig_t *serialConfig);
110 void failsafeInit(rxConfig_t *intialRxConfig, uint16_t deadband3d_throttle);
111 pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init);
112 #ifdef USE_SERVOS
113 void mixerInit(mixerMode_e mixerMode, motorMixer_t *customMotorMixers, servoMixer_t *customServoMixers);
114 #else
115 void mixerInit(mixerMode_e mixerMode, motorMixer_t *customMotorMixers);
116 #endif
117 void mixerUsePWMIOConfiguration(void);
118 void rxInit(rxConfig_t *rxConfig, modeActivationCondition_t *modeActivationConditions);
119 void gpsPreInit(gpsConfig_t *initialGpsConfig);
120 void gpsInit(serialConfig_t *serialConfig, gpsConfig_t *initialGpsConfig);
121 void imuInit(void);
122 void displayInit(rxConfig_t *intialRxConfig);
123 void ledStripInit(ledConfig_t *ledConfigsToUse, hsvColor_t *colorsToUse);
124 void spektrumBind(rxConfig_t *rxConfig);
126 #ifdef STM32F303xC
127 // from system_stm32f30x.c
128 void SetSysClock(void);
129 #endif
130 #ifdef STM32F10X
131 // from system_stm32f10x.c
132 void SetSysClock(bool overclock);
133 #endif
135 typedef enum {
136 SYSTEM_STATE_INITIALISING = 0,
137 SYSTEM_STATE_CONFIG_LOADED = (1 << 0),
138 SYSTEM_STATE_SENSORS_READY = (1 << 1),
139 SYSTEM_STATE_MOTORS_READY = (1 << 2),
140 SYSTEM_STATE_READY = (1 << 7)
141 } systemState_e;
143 static uint8_t systemState = SYSTEM_STATE_INITIALISING;
145 void flashLedsAndBeep(void)
147 LED1_ON;
148 LED0_OFF;
149 for (uint8_t i = 0; i < 10; i++) {
150 LED1_TOGGLE;
151 LED0_TOGGLE;
152 delay(25);
153 if (!(getPreferedBeeperOffMask() & (1 << (BEEPER_SYSTEM_INIT - 1))))
154 BEEP_ON;
155 delay(25);
156 BEEP_OFF;
158 LED0_OFF;
159 LED1_OFF;
162 void init(void)
164 uint8_t i;
165 drv_pwm_config_t pwm_params;
167 printfSupportInit();
169 initEEPROM();
171 ensureEEPROMContainsValidData();
172 readEEPROM();
174 systemState |= SYSTEM_STATE_CONFIG_LOADED;
176 #ifdef STM32F303
177 // start fpu
178 SCB->CPACR = (0x3 << (10*2)) | (0x3 << (11*2));
179 #endif
181 #ifdef STM32F303xC
182 SetSysClock();
183 #endif
184 #ifdef STM32F10X
185 // Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers
186 // Configure the Flash Latency cycles and enable prefetch buffer
187 SetSysClock(masterConfig.emf_avoidance);
188 #endif
189 i2cSetOverclock(masterConfig.i2c_overclock);
191 #ifdef USE_HARDWARE_REVISION_DETECTION
192 detectHardwareRevision();
193 #endif
195 systemInit();
197 // Latch active features to be used for feature() in the remainder of init().
198 latchActiveFeatures();
200 ledInit();
202 #ifdef SPEKTRUM_BIND
203 if (feature(FEATURE_RX_SERIAL)) {
204 switch (masterConfig.rxConfig.serialrx_provider) {
205 case SERIALRX_SPEKTRUM1024:
206 case SERIALRX_SPEKTRUM2048:
207 // Spektrum satellite binding if enabled on startup.
208 // Must be called before that 100ms sleep so that we don't lose satellite's binding window after startup.
209 // The rest of Spektrum initialization will happen later - via spektrumInit()
210 spektrumBind(&masterConfig.rxConfig);
211 break;
214 #endif
216 delay(500);
218 timerInit(); // timer must be initialized before any channel is allocated
220 serialInit(&masterConfig.serialConfig, feature(FEATURE_SOFTSERIAL));
222 #ifdef USE_SERVOS
223 mixerInit(masterConfig.mixerMode, masterConfig.customMotorMixer, masterConfig.customServoMixer);
224 #else
225 mixerInit(masterConfig.mixerMode, masterConfig.customMotorMixer);
226 #endif
228 memset(&pwm_params, 0, sizeof(pwm_params));
230 #ifdef SONAR
231 sonarGPIOConfig_t sonarGPIOConfig;
232 if (feature(FEATURE_SONAR)) {
233 const sonarHcsr04Hardware_t *sonarHardware = sonarGetHardwareConfiguration(masterConfig.batteryConfig.currentMeterType);
234 sonarGPIOConfig.gpio = sonarHardware->echo_gpio;
235 sonarGPIOConfig.triggerPin = sonarHardware->echo_pin;
236 sonarGPIOConfig.echoPin = sonarHardware->trigger_pin;
237 pwm_params.sonarGPIOConfig = &sonarGPIOConfig;
239 pwm_params.useSonar = feature(FEATURE_SONAR);
240 #endif
242 // when using airplane/wing mixer, servo/motor outputs are remapped
243 if (masterConfig.mixerMode == MIXER_AIRPLANE || masterConfig.mixerMode == MIXER_FLYING_WING || masterConfig.mixerMode == MIXER_CUSTOM_AIRPLANE)
244 pwm_params.airplane = true;
245 else
246 pwm_params.airplane = false;
247 #if defined(USE_USART2) && defined(STM32F10X)
248 pwm_params.useUART2 = doesConfigurationUsePort(SERIAL_PORT_USART2);
249 #endif
250 #ifdef STM32F303xC
251 pwm_params.useUART3 = doesConfigurationUsePort(SERIAL_PORT_USART3);
252 #endif
253 pwm_params.useVbat = feature(FEATURE_VBAT);
254 pwm_params.useSoftSerial = feature(FEATURE_SOFTSERIAL);
255 pwm_params.useParallelPWM = feature(FEATURE_RX_PARALLEL_PWM);
256 pwm_params.useRSSIADC = feature(FEATURE_RSSI_ADC);
257 pwm_params.useCurrentMeterADC = feature(FEATURE_CURRENT_METER)
258 && masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC;
259 pwm_params.useLEDStrip = feature(FEATURE_LED_STRIP);
260 pwm_params.usePPM = feature(FEATURE_RX_PPM);
261 pwm_params.useSerialRx = feature(FEATURE_RX_SERIAL);
263 #ifdef USE_SERVOS
264 pwm_params.useServos = isServoOutputEnabled();
265 pwm_params.useChannelForwarding = feature(FEATURE_CHANNEL_FORWARDING);
266 pwm_params.servoCenterPulse = masterConfig.escAndServoConfig.servoCenterPulse;
267 pwm_params.servoPwmRate = masterConfig.servo_pwm_rate;
268 #endif
270 pwm_params.useOneshot = feature(FEATURE_ONESHOT125);
271 pwm_params.motorPwmRate = masterConfig.motor_pwm_rate;
272 pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand;
273 if (feature(FEATURE_3D))
274 pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d;
275 if (pwm_params.motorPwmRate > 500)
276 pwm_params.idlePulse = 0; // brushed motors
278 pwmRxInit(masterConfig.inputFilteringMode);
280 // pwmInit() needs to be called as soon as possible for ESC compatibility reasons
281 pwmInit(&pwm_params);
283 mixerUsePWMIOConfiguration();
285 if (!feature(FEATURE_ONESHOT125))
286 motorControlEnable = true;
288 systemState |= SYSTEM_STATE_MOTORS_READY;
290 #ifdef BEEPER
291 beeperConfig_t beeperConfig = {
292 .gpioPeripheral = BEEP_PERIPHERAL,
293 .gpioPin = BEEP_PIN,
294 .gpioPort = BEEP_GPIO,
295 #ifdef BEEPER_INVERTED
296 .gpioMode = Mode_Out_PP,
297 .isInverted = true
298 #else
299 .gpioMode = Mode_Out_OD,
300 .isInverted = false
301 #endif
303 #ifdef NAZE
304 if (hardwareRevision >= NAZE32_REV5) {
305 // naze rev4 and below used opendrain to PNP for buzzer. Rev5 and above use PP to NPN.
306 beeperConfig.gpioMode = Mode_Out_PP;
307 beeperConfig.isInverted = true;
309 #endif
311 beeperInit(&beeperConfig);
312 #endif
314 #ifdef INVERTER
315 initInverter();
316 #endif
319 #ifdef USE_SPI
320 spiInit(SPI1);
321 spiInit(SPI2);
322 #endif
324 #ifdef USE_HARDWARE_REVISION_DETECTION
325 updateHardwareRevision();
326 #endif
328 #if defined(NAZE)
329 if (hardwareRevision == NAZE32_SP) {
330 serialRemovePort(SERIAL_PORT_SOFTSERIAL2);
331 } else {
332 serialRemovePort(SERIAL_PORT_USART3);
334 #endif
336 #if defined(SPRACINGF3) && defined(SONAR) && defined(USE_SOFTSERIAL2)
337 if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) {
338 serialRemovePort(SERIAL_PORT_SOFTSERIAL2);
340 #endif
343 #ifdef USE_I2C
344 #if defined(NAZE)
345 if (hardwareRevision != NAZE32_SP) {
346 i2cInit(I2C_DEVICE);
347 } else {
348 if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {
349 i2cInit(I2C_DEVICE);
352 #elif defined(CC3D)
353 if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {
354 i2cInit(I2C_DEVICE);
356 #else
357 i2cInit(I2C_DEVICE);
358 #endif
359 #endif
361 #ifdef USE_ADC
362 drv_adc_config_t adc_params;
364 adc_params.enableVBat = feature(FEATURE_VBAT);
365 adc_params.enableRSSI = feature(FEATURE_RSSI_ADC);
366 adc_params.enableCurrentMeter = feature(FEATURE_CURRENT_METER);
367 adc_params.enableExternal1 = false;
368 #ifdef OLIMEXINO
369 adc_params.enableExternal1 = true;
370 #endif
371 #ifdef NAZE
372 // optional ADC5 input on rev.5 hardware
373 adc_params.enableExternal1 = (hardwareRevision >= NAZE32_REV5);
374 #endif
376 adcInit(&adc_params);
377 #endif
379 initBoardAlignment(&masterConfig.boardAlignment);
381 #ifdef DISPLAY
382 if (feature(FEATURE_DISPLAY)) {
383 displayInit(&masterConfig.rxConfig);
385 #endif
387 #ifdef GPS
388 if (feature(FEATURE_GPS)) {
389 gpsPreInit(&masterConfig.gpsConfig);
391 #endif
393 // Set gyro sampling rate divider before initialization
394 gyroSetSampleRate(masterConfig.looptime, masterConfig.gyro_lpf, masterConfig.gyroSync, masterConfig.gyroSyncDenominator);
396 if (!sensorsAutodetect(&masterConfig.sensorAlignmentConfig, masterConfig.gyro_lpf,
397 masterConfig.acc_hardware, masterConfig.mag_hardware, masterConfig.baro_hardware, currentProfile->mag_declination)) {
399 // if gyro was not detected due to whatever reason, we give up now.
400 failureMode(FAILURE_MISSING_ACC);
403 systemState |= SYSTEM_STATE_SENSORS_READY;
405 LED1_ON;
406 LED0_OFF;
407 for (i = 0; i < 10; i++) {
408 LED1_TOGGLE;
409 LED0_TOGGLE;
410 delay(25);
411 BEEP_ON;
412 delay(25);
413 BEEP_OFF;
415 LED0_OFF;
416 LED1_OFF;
418 #ifdef MAG
419 if (sensors(SENSOR_MAG))
420 compassInit();
421 #endif
423 imuInit();
425 mspInit(&masterConfig.serialConfig);
427 #ifdef USE_CLI
428 cliInit(&masterConfig.serialConfig);
429 #endif
431 failsafeInit(&masterConfig.rxConfig, masterConfig.flight3DConfig.deadband3d_throttle);
433 rxInit(&masterConfig.rxConfig, currentProfile->modeActivationConditions);
435 #ifdef GPS
436 if (feature(FEATURE_GPS)) {
437 gpsInit(
438 &masterConfig.serialConfig,
439 &masterConfig.gpsConfig
442 #endif
444 #ifdef NAV
445 navigationInit(
446 &masterConfig.navConfig,
447 &currentProfile->pidProfile,
448 &currentProfile->rcControlsConfig,
449 &masterConfig.rxConfig,
450 &masterConfig.flight3DConfig,
451 &masterConfig.escAndServoConfig
453 #endif
455 #ifdef SONAR
456 if (feature(FEATURE_SONAR)) {
457 sonarInit();
459 #endif
461 #ifdef LED_STRIP
462 ledStripInit(masterConfig.ledConfigs, masterConfig.colors);
464 if (feature(FEATURE_LED_STRIP)) {
465 ledStripEnable();
467 #endif
469 #ifdef TELEMETRY
470 if (feature(FEATURE_TELEMETRY)) {
471 telemetryInit();
473 #endif
475 #ifdef USE_FLASHFS
476 #ifdef NAZE
477 if (hardwareRevision == NAZE32_REV5) {
478 m25p16_init();
480 #elif defined(USE_FLASH_M25P16)
481 m25p16_init();
482 #endif
484 flashfsInit();
485 #endif
487 #ifdef BLACKBOX
488 initBlackbox();
489 #endif
491 gyroSetCalibrationCycles(CALIBRATING_GYRO_CYCLES);
492 #ifdef BARO
493 baroSetCalibrationCycles(CALIBRATING_BARO_CYCLES);
494 #endif
496 // start all timers
497 // TODO - not implemented yet
498 timerStart();
500 ENABLE_STATE(SMALL_ANGLE);
501 DISABLE_ARMING_FLAG(PREVENT_ARMING);
503 #ifdef SOFTSERIAL_LOOPBACK
504 // FIXME this is a hack, perhaps add a FUNCTION_LOOPBACK to support it properly
505 loopbackPort = (serialPort_t*)&(softSerialPorts[0]);
506 if (!loopbackPort->vTable) {
507 loopbackPort = openSoftSerial(0, NULL, 19200, SERIAL_NOT_INVERTED);
509 serialPrint(loopbackPort, "LOOPBACK\r\n");
510 #endif
512 // Now that everything has powered up the voltage and cell count be determined.
514 if (feature(FEATURE_VBAT | FEATURE_CURRENT_METER))
515 batteryInit(&masterConfig.batteryConfig);
517 #ifdef CJMCU
518 LED2_ON;
519 #endif
521 // Latch active features AGAIN since some may be modified by init().
522 latchActiveFeatures();
523 motorControlEnable = true;
525 systemState |= SYSTEM_STATE_READY;
528 #ifdef SOFTSERIAL_LOOPBACK
529 void processLoopback(void) {
530 if (loopbackPort) {
531 uint8_t bytesWaiting;
532 while ((bytesWaiting = serialRxBytesWaiting(loopbackPort))) {
533 uint8_t b = serialRead(loopbackPort);
534 serialWrite(loopbackPort, b);
538 #else
539 #define processLoopback()
540 #endif
542 int main(void) {
543 init();
545 /* Setup scheduler */
546 schedulerInit();
548 rescheduleTask(TASK_GYROPID, targetLooptime);
549 setTaskEnabled(TASK_GYROPID, true);
551 setTaskEnabled(TASK_SERIAL, true);
552 #ifdef BEEPER
553 setTaskEnabled(TASK_BEEPER, true);
554 #endif
555 setTaskEnabled(TASK_BATTERY, feature(FEATURE_VBAT) || feature(FEATURE_CURRENT_METER));
556 setTaskEnabled(TASK_RX, true);
557 #ifdef GPS
558 setTaskEnabled(TASK_GPS, feature(FEATURE_GPS));
559 #endif
560 #ifdef MAG
561 setTaskEnabled(TASK_COMPASS, sensors(SENSOR_MAG));
562 #endif
563 #ifdef BARO
564 setTaskEnabled(TASK_BARO, sensors(SENSOR_BARO));
565 #endif
566 #ifdef SONAR
567 setTaskEnabled(TASK_SONAR, sensors(SENSOR_SONAR));
568 #endif
569 #ifdef DISPLAY
570 setTaskEnabled(TASK_DISPLAY, feature(FEATURE_DISPLAY));
571 #endif
572 #ifdef TELEMETRY
573 setTaskEnabled(TASK_TELEMETRY, feature(FEATURE_TELEMETRY));
574 #endif
575 #ifdef LED_STRIP
576 setTaskEnabled(TASK_LEDSTRIP, feature(FEATURE_LED_STRIP));
577 #endif
579 while (1) {
580 scheduler();
581 processLoopback();
585 void HardFault_Handler(void)
587 // fall out of the sky
588 uint8_t requiredState = SYSTEM_STATE_CONFIG_LOADED | SYSTEM_STATE_MOTORS_READY;
589 if ((systemState & requiredState) == requiredState) {
590 stopMotors();
592 while (1);