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)
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/>.
23 #include "build/version.h"
27 The purpose of this file is to enable / disable any firmware "gates" for features and drivers
28 that require hardware resources that are either available or not available after the target.h
31 It should also be used to define anything that should be defined (and is required), but is not
32 already, to some sort of defaults.
34 CLOUD_BUILD and CORE_BUILD should not be referenced here.
36 NOTE: for 4.5 we will be removing any conditions related to specific MCU types, instead
37 these should be defined in the target.h or in a file that is imported by target.h (in the
38 case of common settings for a given MCU group)
42 #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
43 #define DEFAULT_AUX_CHANNEL_COUNT MAX_AUX_CHANNEL_COUNT
45 #define DEFAULT_AUX_CHANNEL_COUNT 6
49 #if defined(ITCM_RAM_OPTIMISATION) && !defined(DEBUG)
50 #define FAST_CODE __attribute__((section(".tcm_code"))) __attribute__((optimize(ITCM_RAM_OPTIMISATION)))
52 #define FAST_CODE __attribute__((section(".tcm_code")))
54 // Handle case where we'd prefer code to be in ITCM, but it won't fit on the F745
56 #define FAST_CODE_PREF
58 #define FAST_CODE_PREF __attribute__((section(".tcm_code")))
60 #define FAST_CODE_NOINLINE NOINLINE
63 #define FAST_CODE_PREF
64 #define FAST_CODE_NOINLINE
65 #endif // USE_ITCM_RAM
68 #define CCM_CODE __attribute__((section(".ccm_code")))
74 #define FAST_DATA_ZERO_INIT __attribute__ ((section(".fastram_bss"), aligned(4)))
75 #define FAST_DATA __attribute__ ((section(".fastram_data"), aligned(4)))
77 #define FAST_DATA_ZERO_INIT
79 #endif // USE_FAST_DATA
82 BEGIN HARDWARE INCLUSIONS
84 Simplified options for the moment, i.e. adding USE_MAG or USE_BARO and the entire driver suite is added.
85 In the future we can move to specific drivers being added only - to save flash space.
88 #if defined(USE_MAG) && !defined(USE_VIRTUAL_MAG)
89 #define USE_MAG_DATA_READY_SIGNAL
90 #define USE_MAG_HMC5883
91 #define USE_MAG_SPI_HMC5883
92 #define USE_MAG_QMC5883
93 #define USE_MAG_LIS3MDL
94 #define USE_MAG_AK8963
95 #define USE_MAG_MPU925X_AK8963
96 #define USE_MAG_SPI_AK8963
97 #define USE_MAG_AK8975
100 #if defined(USE_RX_CC2500)
102 #if !defined(USE_RX_SPI)
106 #define USE_RX_CC2500_SPI_PA_LNA
107 #define USE_RX_CC2500_SPI_DIVERSITY
109 #define USE_RX_SFHSS_SPI
110 #define USE_RX_REDPINE_SPI
112 #define USE_RX_FRSKY_SPI_D
113 #define USE_RX_FRSKY_SPI_X
114 #define USE_RX_FRSKY_SPI
115 #define USE_RX_FRSKY_SPI_TELEMETRY
117 #define USE_RX_FLYSKY
118 #define USE_RX_FLYSKY_SPI_LED
119 #define USE_RX_SPEKTRUM
120 #define USE_RX_SPEKTRUM_TELEMETRY
122 #endif // defined(USE_RX_CC2500)
124 #if defined(CAMERA_CONTROL_PIN) && defined(USE_VTX) && !defined(USE_CAMERA_CONTROL)
125 #define USE_CAMERA_CONTROL
128 /* END HARDWARE INCLUSIONS */
130 #if defined(USE_VTX_RTC6705_SOFTSPI)
131 #define USE_VTX_RTC6705
135 #undef USE_ESC_SENSOR
138 #ifndef USE_ESC_SENSOR
139 #undef USE_ESC_SENSOR_TELEMETRY
142 // XXX Followup implicit dependencies among DASHBOARD, display_xxx and USE_I2C.
143 // XXX This should eventually be cleaned up.
145 #undef USE_I2C_OLED_DISPLAY
149 #define USE_I2C_OLED_DISPLAY
153 // Remove USE_BARO_BMP280 and USE_BARO_MS5611 if USE_I2C is not defined.
154 #if !defined(USE_I2C)
155 #if defined(USE_BARO_BMP280)
156 #undef USE_BARO_BMP280
158 #if defined(USE_BARO_MS5611)
159 #undef USE_BARO_MS5611
163 // Add VARIO if BARO or GPS is defined. Remove when none defined.
164 #if defined(USE_BARO) || defined(USE_GPS)
172 #if !defined(USE_SERIALRX)
173 #undef USE_SERIALRX_CRSF
174 #undef USE_SERIALRX_IBUS
175 #undef USE_SERIALRX_JETIEXBUS
176 #undef USE_SERIALRX_SBUS
177 #undef USE_SERIALRX_SPEKTRUM
178 #undef USE_SERIALRX_SUMD
179 #undef USE_SERIALRX_SUMH
180 #undef USE_SERIALRX_XBUS
181 #undef USE_SERIALRX_FPORT
184 #if !defined(USE_TELEMETRY)
185 #undef USE_TELEMETRY_CRSF
186 #undef USE_TELEMETRY_GHST
187 #undef USE_TELEMETRY_FRSKY_HUB
188 #undef USE_TELEMETRY_HOTT
189 #undef USE_TELEMETRY_IBUS
190 #undef USE_TELEMETRY_IBUS_EXTENDED
191 #undef USE_TELEMETRY_JETIEXBUS
192 #undef USE_TELEMETRY_LTM
193 #undef USE_TELEMETRY_MAVLINK
194 #undef USE_TELEMETRY_SMARTPORT
195 #undef USE_TELEMETRY_SRXL
197 #ifdef USE_SERIALRX_FPORT
198 #ifndef USE_TELEMETRY
199 #define USE_TELEMETRY
201 #ifndef USE_TELEMETRY_SMARTPORT
202 #define USE_TELEMETRY_SMARTPORT
207 #if defined(USE_TELEMETRY_IBUS_EXTENDED) && !defined(USE_TELEMETRY_IBUS)
208 #define USE_TELEMETRY_IBUS
211 #if !defined(USE_SERIALRX_CRSF)
212 #undef USE_TELEMETRY_CRSF
213 #undef USE_CRSF_LINK_STATISTICS
217 #if !defined(USE_RX_EXPRESSLRS) && !defined(USE_SERIALRX_CRSF)
218 #undef USE_RX_RSSI_DBM
221 #if !defined(USE_SERIALRX_GHST)
222 #undef USE_TELEMETRY_GHST
225 #if !defined(USE_TELEMETRY_CRSF) || !defined(USE_CMS)
226 #undef USE_CRSF_CMS_TELEMETRY
229 #if !defined(USE_TELEMETRY_CRSF)
233 #if !defined(USE_SERIALRX_JETIEXBUS)
234 #undef USE_TELEMETRY_JETIEXBUS
237 #if !defined(USE_TELEMETRY_IBUS)
238 #undef USE_TELEMETRY_IBUS_EXTENDED
241 // If USE_SERIALRX_SPEKTRUM was dropped by a target, drop all related options
242 #ifndef USE_SERIALRX_SPEKTRUM
243 #undef USE_SPEKTRUM_BIND
244 #undef USE_SPEKTRUM_BIND_PLUG
245 #undef USE_SPEKTRUM_REAL_RSSI
246 #undef USE_SPEKTRUM_VIRTUAL_RSSI
247 #undef USE_SPEKTRUM_RSSI_PERCENT_CONVERSION
248 #undef USE_SPEKTRUM_VTX_CONTROL
249 #undef USE_SPEKTRUM_VTX_TELEMETRY
250 #undef USE_TELEMETRY_SRXL
253 #if !defined(USE_CMS) || !defined(USE_TELEMETRY_SRXL)
254 #undef USE_SPEKTRUM_CMS_TELEMETRY
257 #if defined(USE_SERIALRX_SBUS) || defined(USE_SERIALRX_FPORT)
258 #define USE_SBUS_CHANNELS
261 #if !defined(USE_TELEMETRY_SMARTPORT) && !defined(USE_TELEMETRY_CRSF) && !defined(USE_TELEMETRY_GHST)
262 #undef USE_MSP_OVER_TELEMETRY
265 #if !defined(USE_RX_MSP) && defined(USE_RX_MSP_OVERRIDE)
266 #undef USE_RX_MSP_OVERRIDE
269 /* If either VTX_CONTROL or VTX_COMMON is undefined then remove common code and device drivers */
270 #if !defined(USE_VTX_COMMON) || !defined(USE_VTX_CONTROL)
271 #undef USE_VTX_COMMON
272 #undef USE_VTX_CONTROL
274 #undef USE_VTX_SMARTAUDIO
279 // Some target doesn't define USE_ADC which USE_ADC_INTERNAL depends on
281 #undef USE_ADC_INTERNAL
284 #if (defined(USE_SDCARD) || defined(USE_FLASH)) && !defined(USE_BLACKBOX)
289 #define USE_FLASH_TOOLS
293 #if (defined(USE_FLASH_W25M512) || defined(USE_FLASH_W25Q128FV)) && !defined(USE_FLASH_M25P16)
294 #define USE_FLASH_M25P16
297 #if defined(USE_FLASH_W25M02G) && !defined(USE_FLASH_W25N01G)
298 #define USE_FLASH_W25N01G
301 #if (defined(USE_FLASH_M25P16) || defined(USE_FLASH_W25N01G)) && !defined(USE_FLASH_W25M)
302 #define USE_FLASH_W25M
305 #if defined(USE_FLASH_M25P16) || defined(USE_FLASH_W25M) || defined(USE_FLASH_W25N01G) || defined(USE_FLASH_W25Q128FV)
306 #define USE_FLASH_CHIP
309 #if defined(USE_SPI) && (defined(USE_FLASH_M25P16) || defined(USE_FLASH_W25M512) || defined(USE_FLASH_W25N01G) || defined(USE_FLASH_W25M02G))
310 #define USE_FLASH_SPI
313 #if defined(USE_QUADSPI) && (defined(USE_FLASH_W25Q128FV) || defined(USE_FLASH_W25N01G))
314 #define USE_FLASH_QUADSPI
317 #if defined(USE_OCTOSPI) && (defined(USE_FLASH_W25Q128FV))
318 #define USE_FLASH_OCTOSPI
321 #ifndef USE_FLASH_CHIP
322 #undef USE_FLASH_TOOLS
326 #if (!defined(USE_SDCARD) && !defined(USE_FLASHFS)) || !defined(USE_BLACKBOX)
330 #if !defined(USE_SDCARD)
331 #undef USE_SDCARD_SDIO
332 #undef USE_SDCARD_SPI
335 #if !defined(USE_VCP)
336 #undef USE_USB_CDC_HID
340 #if defined(USE_USB_CDC_HID) || defined(USE_USB_MSC)
341 #define USE_USB_ADVANCED_PROFILES
344 #if defined(USE_VTX) && !defined(DEFAULT_FEATURES)
345 #define DEFAULT_FEATURES FEATURE_VTX
348 #if !defined(USE_OSD)
349 #undef USE_RX_LINK_QUALITY_INFO
350 #undef USE_OSD_PROFILES
351 #undef USE_OSD_STICK_OVERLAY
352 #undef USE_RX_LINK_UPLINK_POWER
355 // Older ACC/GYRO sensors use MPU6500 driver
356 #if !defined(USE_ACC_MPU6500) && (defined(USE_ACC_ICM20601) || defined(USE_ACC_ICM20602) || defined(USE_ACC_ICM20608G))
357 #define USE_ACC_MPU6500
359 #if !defined(USE_ACC_SPI_MPU6500) && (defined(USE_ACC_SPI_MPU9250) || defined(USE_ACC_SPI_ICM20601) || defined(USE_ACC_SPI_ICM20602) || defined(USE_ACC_SPI_ICM20608G))
360 #define USE_ACC_SPI_MPU6500
362 #if !defined(USE_GYRO_MPU6500) && (defined(USE_GYRO_ICM20601) || defined(USE_GYRO_ICM20602) || defined(USE_GYRO_ICM20608G))
363 #define USE_GYRO_MPU6500
365 #if !defined(USE_GYRO_SPI_MPU6500) && (defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20602) || defined(USE_GYRO_SPI_ICM20608G))
366 #define USE_GYRO_SPI_MPU6500
369 // Generate USE_SPI_GYRO or USE_I2C_GYRO
370 #if defined(USE_GYRO_L3G4200D) || defined(USE_GYRO_MPU3050) || defined(USE_GYRO_MPU6000) || defined(USE_GYRO_MPU6050) || defined(USE_GYRO_MPU6500)
374 #if defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_L3GD20) || defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) || defined(USE_ACCGYRO_BMI160) || defined(USE_ACCGYRO_BMI270)
378 #ifndef SIMULATOR_BUILD
388 // CX10 is a special case of SPI RX which requires XN297
389 #if defined(USE_RX_CX10)
393 // Setup crystal frequency on F4 for backward compatibility
394 // Should be set to zero for generic targets to ensure USB is working
395 // when unconfigured for targets with non-standard crystal.
396 // Can be set at runtime with with CLI parameter 'system_hse_mhz'.
397 #ifndef SYSTEM_HSE_MHZ
398 #define SYSTEM_HSE_MHZ 0
401 // Number of pins that needs pre-init
403 #ifndef SPI_PREINIT_COUNT
404 // 2 x 8 (GYROx2, BARO, MAG, MAX, FLASHx2, RX)
405 #define SPI_PREINIT_COUNT 16
413 #if (!defined(USE_FLASHFS) || !defined(USE_RTC_TIME) || !defined(USE_USB_MSC) || !defined(USE_PERSISTENT_OBJECTS))
414 #undef USE_PERSISTENT_MSC_RTC
417 #if !defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) && !defined(USE_SERIAL_4WAY_SK_BOOTLOADER)
418 #undef USE_SERIAL_4WAY_BLHELI_INTERFACE
419 #elif !defined(USE_SERIAL_4WAY_BLHELI_INTERFACE) && (defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) || defined(USE_SERIAL_4WAY_SK_BOOTLOADER))
420 #ifndef USE_SERIAL_4WAY_BLHELI_INTERFACE
421 #define USE_SERIAL_4WAY_BLHELI_INTERFACE
425 #if defined(USE_RX_PWM) || defined(USE_DSHOT) || defined(USE_LED_STRIP) || defined(USE_TRANSPONDER) || defined(USE_BEEPER) || defined(USE_SERIAL_4WAY_BLHELI_INTERFACE)
426 #ifndef USE_PWM_OUTPUT
427 #define USE_PWM_OUTPUT
431 #if !defined(USE_LED_STRIP)
432 #undef USE_LED_STRIP_STATUS_MODE
435 #if defined(USE_MAX7456) || defined(USE_FRSKYOSD) || defined(USE_MSP_DISPLAYPORT)
436 #ifndef USE_VIDEO_SYSTEM
437 #define USE_VIDEO_SYSTEM
441 #if defined(USE_LED_STRIP) && !defined(USE_LED_STRIP_STATUS_MODE)
442 #define USE_WS2811_SINGLE_COLOUR
445 #if defined(SIMULATOR_BUILD) || defined(UNIT_TEST)
446 // This feature uses 'arm_math.h', which does not exist for x86.
447 #undef USE_DYN_NOTCH_FILTER
451 #undef USE_CMS_FAILSAFE_MENU
455 #undef USE_DSHOT_TELEMETRY
456 #undef USE_DSHOT_BITBANG
459 #ifndef USE_DSHOT_TELEMETRY
460 #undef USE_RPM_FILTER
461 #undef USE_DSHOT_TELEMETRY_STATS
464 #if !defined(USE_BOARD_INFO)
468 #if !defined(USE_ACC)
469 #undef USE_GPS_RESCUE
470 #undef USE_ACRO_TRAINER
473 #if (!defined(USE_GPS_RESCUE) || !defined(USE_CMS_FAILSAFE_MENU))
474 #undef USE_CMS_GPS_RESCUE_MENU
482 #if defined(USE_DMA_SPEC)
483 #define USE_TIMER_DMA
485 #undef USE_TIMER_MGMT
488 #if defined(USE_TIMER_MGMT)
492 #if !defined(USE_RANGEFINDER)
493 #undef USE_RANGEFINDER_HCSR04
494 #undef USE_RANGEFINDER_SRF10
495 #undef USE_RANGEFINDER_HCSR04_I2C
496 #undef USE_RANGEFINDER_VL53L0X
497 #undef USE_RANGEFINDER_UIB
498 #undef USE_RANGEFINDER_TF
501 #ifndef USE_GPS_RESCUE
502 #undef USE_CMS_GPS_RESCUE_MENU
505 // TODO: Remove this once HAL support is fixed for ESCSERIAL
510 #if defined(CONFIG_IN_RAM) || defined(CONFIG_IN_FILE) || defined(CONFIG_IN_EXTERNAL_FLASH) || defined(CONFIG_IN_SDCARD) || defined(CONFIG_IN_MEMORY_MAPPED_FLASH)
512 #define EEPROM_SIZE 4096
514 extern uint8_t eepromData
[EEPROM_SIZE
];
515 #define __config_start (*eepromData)
516 #define __config_end (*ARRAYEND(eepromData))
518 #ifndef CONFIG_IN_FLASH
519 #define CONFIG_IN_FLASH
521 extern uint8_t __config_start
; // configured via linker script when building binaries.
522 extern uint8_t __config_end
;
525 #if defined(USE_EXST) && !defined(RAMBASED)
526 #define USE_FLASH_BOOT_LOADER
529 #if defined(USE_FLASH_MEMORY_MAPPED)
530 #if !defined(USE_RAM_CODE)
534 #define MMFLASH_CODE RAM_CODE
535 #define MMFLASH_CODE_NOINLINE RAM_CODE NOINLINE
537 #define MMFLASH_DATA FAST_DATA
538 #define MMFLASH_DATA_ZERO_INIT FAST_DATA_ZERO_INIT
541 #define MMFLASH_CODE_NOINLINE
543 #define MMFLASH_DATA_ZERO_INIT
547 // RAM_CODE for methods that need to be in RAM, but don't need to be in the fastest type of memory.
548 // Note: if code is marked as RAM_CODE it *MUST* be in RAM, there is no alternative unlike functions marked with FAST_CODE/CCM_CODE
549 #define RAM_CODE __attribute__((section(".ram_code")))
552 #if !defined(USE_RPM_FILTER)
556 #ifndef USE_ITERM_RELAX
557 #undef USE_ABSOLUTE_CONTROL
560 #if defined(USE_RX_EXPRESSLRS)
561 // ELRS depends on CRSF telemetry
562 #if !defined(USE_TELEMETRY)
563 #define USE_TELEMETRY
565 #if !defined(USE_TELEMETRY_CRSF)
566 #define USE_TELEMETRY_CRSF
568 #if !defined(USE_CRSF_LINK_STATISTICS)
569 #define USE_CRSF_LINK_STATISTICS
571 #if !defined(USE_SERIALRX_CRSF)
572 #define USE_SERIALRX_CRSF
576 #if defined(USE_RX_SPI) || defined(USE_SERIALRX_SRXL2)
581 #undef USE_GPS_PLUS_CODES