Missing define to activate TABLE_VIDEO_SYSTEM (#12200)
[betaflight.git] / src / main / target / common_pre.h
blob66c009e35bdf6b6580cff852b4ca8060eb118944
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 #pragma once
23 #define USE_PARAMETER_GROUPS
24 // type conversion warnings.
25 // -Wconversion can be turned on to enable the process of eliminating these warnings
26 //#pragma GCC diagnostic warning "-Wconversion"
27 #pragma GCC diagnostic ignored "-Wsign-conversion"
28 // -Wpadded can be turned on to check padding of structs
29 //#pragma GCC diagnostic warning "-Wpadded"
31 #if !defined(CLOUD_BUILD) && !defined(SITL)
32 #define USE_DSHOT
33 #endif
35 #ifdef USE_DSHOT
36 #define USE_DSHOT_BITBANG
37 #define USE_DSHOT_TELEMETRY
38 #define USE_DSHOT_TELEMETRY_STATS
39 #endif
41 #ifdef STM32F4
42 #if defined(STM32F40_41xxx)
43 #define USE_FAST_DATA
44 #endif
46 #define USE_RPM_FILTER
47 #define USE_DYN_IDLE
48 #define USE_DYN_NOTCH_FILTER
49 #define USE_ADC_INTERNAL
50 #define USE_USB_CDC_HID
51 #define USE_USB_MSC
52 #define USE_PERSISTENT_MSC_RTC
53 #define USE_MCO
54 #define USE_DMA_SPEC
55 #define USE_TIMER_MGMT
56 #define USE_PERSISTENT_OBJECTS
57 #define USE_CUSTOM_DEFAULTS_ADDRESS
58 #define USE_LATE_TASK_STATISTICS
60 #if defined(STM32F40_41xxx) || defined(STM32F411xE)
61 #define USE_OVERCLOCK
62 #endif
63 #endif // STM32F4
65 #ifdef STM32F7
66 #define USE_ITCM_RAM
67 #define ITCM_RAM_OPTIMISATION "-O2", "-freorder-blocks-algorithm=simple"
68 #define USE_FAST_DATA
69 #define USE_RPM_FILTER
70 #define USE_DYN_IDLE
71 #define USE_DYN_NOTCH_FILTER
72 #define USE_OVERCLOCK
73 #define USE_ADC_INTERNAL
74 #define USE_USB_CDC_HID
75 #define USE_USB_MSC
76 #define USE_PERSISTENT_MSC_RTC
77 #define USE_MCO
78 #define USE_DMA_SPEC
79 #define USE_TIMER_MGMT
80 #define USE_PERSISTENT_OBJECTS
81 #define USE_CUSTOM_DEFAULTS_ADDRESS
82 #define USE_LATE_TASK_STATISTICS
83 #endif // STM32F7
85 #ifdef STM32H7
87 #ifdef USE_DSHOT
88 #define USE_DSHOT_CACHE_MGMT
89 #endif
91 #define USE_ITCM_RAM
92 #define USE_FAST_DATA
93 #define USE_RPM_FILTER
94 #define USE_DYN_IDLE
95 #define USE_DYN_NOTCH_FILTER
96 #define USE_ADC_INTERNAL
97 #define USE_USB_CDC_HID
98 #define USE_DMA_SPEC
99 #define USE_TIMER_MGMT
100 #define USE_PERSISTENT_OBJECTS
101 #define USE_DMA_RAM
102 #define USE_USB_MSC
103 #define USE_RTC_TIME
104 #define USE_PERSISTENT_MSC_RTC
105 #define USE_LATE_TASK_STATISTICS
106 #endif
108 #ifdef STM32G4
109 #define USE_RPM_FILTER
110 #define USE_DYN_IDLE
111 #define USE_OVERCLOCK
112 #define USE_DYN_NOTCH_FILTER
113 #define USE_ADC_INTERNAL
114 #define USE_USB_MSC
115 #define USE_USB_CDC_HID
116 #define USE_MCO
117 #define USE_DMA_SPEC
118 #define USE_TIMER_MGMT
119 #define USE_LATE_TASK_STATISTICS
120 #endif
122 #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
123 #define TASK_GYROPID_DESIRED_PERIOD 125 // 125us = 8kHz
124 #define SCHEDULER_DELAY_LIMIT 10
125 #else
126 #define TASK_GYROPID_DESIRED_PERIOD 1000 // 1000us = 1kHz
127 #define SCHEDULER_DELAY_LIMIT 100
128 #endif
130 #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
131 #define DEFAULT_AUX_CHANNEL_COUNT MAX_AUX_CHANNEL_COUNT
132 #else
133 #define DEFAULT_AUX_CHANNEL_COUNT 6
134 #endif
136 // Set the default cpu_overclock to the first level (108MHz) for F411
137 // Helps with looptime stability as the CPU is borderline when running native gyro sampling
138 #if defined(USE_OVERCLOCK) && defined(STM32F411xE)
139 #define DEFAULT_CPU_OVERCLOCK 1
140 #else
141 #define DEFAULT_CPU_OVERCLOCK 0
142 #endif
144 #if defined(STM32H7)
145 // Move ISRs to fast ram to avoid flash latency.
146 #define FAST_IRQ_HANDLER FAST_CODE
147 #else
148 #define FAST_IRQ_HANDLER
149 #endif
152 #ifdef USE_ITCM_RAM
153 #if defined(ITCM_RAM_OPTIMISATION) && !defined(DEBUG)
154 #define FAST_CODE __attribute__((section(".tcm_code"))) __attribute__((optimize(ITCM_RAM_OPTIMISATION)))
155 #else
156 #define FAST_CODE __attribute__((section(".tcm_code")))
157 #endif
158 // Handle case where we'd prefer code to be in ITCM, but it won't fit on the F745
159 #ifdef STM32F745xx
160 #define FAST_CODE_PREF
161 #else
162 #define FAST_CODE_PREF __attribute__((section(".tcm_code")))
163 #endif
164 #define FAST_CODE_NOINLINE NOINLINE
165 #else
166 #define FAST_CODE
167 #define FAST_CODE_PREF
168 #define FAST_CODE_NOINLINE
169 #endif // USE_ITCM_RAM
171 #ifdef USE_CCM_CODE
172 #define CCM_CODE __attribute__((section(".ccm_code")))
173 #else
174 #define CCM_CODE
175 #endif
177 #ifdef USE_FAST_DATA
178 #define FAST_DATA_ZERO_INIT __attribute__ ((section(".fastram_bss"), aligned(4)))
179 #define FAST_DATA __attribute__ ((section(".fastram_data"), aligned(4)))
180 #else
181 #define FAST_DATA_ZERO_INIT
182 #define FAST_DATA
183 #endif // USE_FAST_DATA
185 #if defined(STM32F4) || defined(STM32G4)
186 // F4 can't DMA to/from CCM (core coupled memory) SRAM (where the stack lives)
187 // On G4 there is no specific DMA target memory
188 #define DMA_DATA_ZERO_INIT
189 #define DMA_DATA
190 #define STATIC_DMA_DATA_AUTO static
191 #elif defined (STM32F7)
192 // F7 has no cache coherency issues DMAing to/from DTCM, otherwise buffers must be cache aligned
193 #define DMA_DATA_ZERO_INIT FAST_DATA_ZERO_INIT
194 #define DMA_DATA FAST_DATA
195 #define STATIC_DMA_DATA_AUTO static DMA_DATA
196 #else
197 // DMA to/from any memory
198 #define DMA_DATA_ZERO_INIT __attribute__ ((section(".dmaram_bss"), aligned(32)))
199 #define DMA_DATA __attribute__ ((section(".dmaram_data"), aligned(32)))
200 #define STATIC_DMA_DATA_AUTO static DMA_DATA
201 #endif
203 #if defined(STM32F4) || defined (STM32H7)
204 // Data in RAM which is guaranteed to not be reset on hot reboot
205 #define PERSISTENT __attribute__ ((section(".persistent_data"), aligned(4)))
206 #endif
208 #ifdef USE_DMA_RAM
209 #if defined(STM32H7)
210 #define DMA_RAM __attribute__((section(".DMA_RAM"), aligned(32)))
211 #define DMA_RW_AXI __attribute__((section(".DMA_RW_AXI"), aligned(32)))
212 extern uint8_t _dmaram_start__;
213 extern uint8_t _dmaram_end__;
214 #elif defined(STM32G4)
215 #define DMA_RAM_R __attribute__((section(".DMA_RAM_R")))
216 #define DMA_RAM_W __attribute__((section(".DMA_RAM_W")))
217 #define DMA_RAM_RW __attribute__((section(".DMA_RAM_RW")))
218 #endif
219 #else
220 #define DMA_RAM
221 #define DMA_RW_AXI
222 #define DMA_RAM_R
223 #define DMA_RAM_W
224 #define DMA_RAM_RW
225 #endif
227 #define USE_MOTOR
228 #define USE_DMA
229 #define USE_TIMER
231 #define USE_CLI
232 #define USE_SERIAL_PASSTHROUGH
233 #define USE_GYRO_REGISTER_DUMP // Adds gyroregisters command to cli to dump configured register values
234 #define USE_IMU_CALC
236 // all the settings for classic build
237 #if !defined(CLOUD_BUILD) && !defined(SITL)
239 #define USE_MAG
241 #if !defined(USE_BARO) && !defined(USE_FAKE_BARO)
242 #define USE_BARO
244 #define USE_BARO_MS5611
245 #define USE_BARO_SPI_MS5611
246 #define USE_BARO_BMP280
247 #define USE_BARO_SPI_BMP280
248 #define USE_BARO_BMP388
249 #define USE_BARO_SPI_BMP388
250 #define USE_BARO_LPS
251 #define USE_BARO_SPI_LPS
252 #define USE_BARO_QMP6988
253 #define USE_BARO_SPI_QMP6988
254 #define USE_BARO_DPS310
255 #define USE_BARO_SPI_DPS310
256 #define USE_BARO_BMP085
257 #define USE_BARO_2SMBP_02B
258 #define USE_BARO_SPI_2SMBP_02B
259 #endif
261 #if !defined(USE_GYRO) && !defined(USE_ACC)
262 #define USE_ACC
263 #define USE_GYRO
265 #define USE_ACC_MPU6500
266 #define USE_GYRO_MPU6500
267 #define USE_ACC_SPI_MPU6000
268 #define USE_GYRO_SPI_MPU6000
269 #define USE_ACC_SPI_MPU6500
270 #define USE_GYRO_SPI_MPU6500
271 #define USE_ACC_SPI_ICM20689
272 #define USE_GYRO_SPI_ICM20689
273 #define USE_ACCGYRO_LSM6DSO
274 #define USE_ACCGYRO_BMI270
275 #define USE_GYRO_SPI_ICM42605
276 #define USE_GYRO_SPI_ICM42688P
277 #define USE_ACC_SPI_ICM42605
278 #define USE_ACC_SPI_ICM42688P
280 #if defined(STM32F405) || defined(STM32F745) || defined(STM32G4) || defined(STM32H7)
281 #define USE_ACC_MPU6050
282 #define USE_GYRO_MPU6050
283 #define USE_ACCGYRO_BMI160
284 #endif
285 #endif
287 #if !defined(USE_EXST) && !defined(USE_FLASH)
288 #define USE_FLASHFS
290 #define USE_FLASH_TOOLS
291 #define USE_FLASH_M25P16
292 #define USE_FLASH_W25N01G // 1Gb NAND flash support
293 #define USE_FLASH_W25M // Stacked die support
294 #define USE_FLASH_W25M512 // 512Kb (256Kb x 2 stacked) NOR flash support
295 #define USE_FLASH_W25M02G // 2Gb (1Gb x 2 stacked) NAND flash support
296 #define USE_FLASH_W25Q128FV // 16MB Winbond 25Q128
298 #endif
300 #ifndef USE_MAX7456
301 #define USE_MAX7456
302 #endif
304 #if !defined(USE_RX_SPI)
305 #define USE_RX_SPI
307 #define USE_RX_CC2500
308 #define USE_RX_EXPRESSLRS
309 #define USE_RX_SX1280
310 #define USE_RX_SX127X
311 #endif // !USE_RX_SPI
313 #if !defined(USE_EXST) && !defined(USE_SDCARD)
314 #define USE_SDCARD
315 #endif
317 #if defined(STM32F405) || defined(STM32F745) || defined(STM32H7)
318 #define USE_VTX_RTC6705
319 #define USE_VTX_RTC6705_SOFTSPI
321 #define USE_TRANSPONDER
323 #define USE_RANGEFINDER
324 #define USE_RANGEFINDER_HCSR04
325 #define USE_RANGEFINDER_TF
326 #endif
328 #define USE_RX_PPM
329 #define USE_RX_PWM
331 #define USE_BRUSHED_ESC_AUTODETECT // Detect if brushed motors are connected and set defaults appropriately to avoid motors spinning on boot
333 #define USE_PINIO
335 #if !defined(USE_SERIAL_RX)
337 #define USE_SERIALRX
338 #define USE_SERIALRX_CRSF // Team Black Sheep Crossfire protocol
339 #define USE_SERIALRX_GHST // ImmersionRC Ghost Protocol
340 #define USE_SERIALRX_IBUS // FlySky and Turnigy receivers
341 #define USE_SERIALRX_SBUS // Frsky and Futaba receivers
342 #define USE_SERIALRX_SPEKTRUM // SRXL, DSM2 and DSMX protocol
343 #define USE_SERIALRX_FPORT // FrSky FPort
344 #define USE_SERIALRX_XBUS // JR
345 #define USE_SERIALRX_SRXL2 // Spektrum SRXL2 protocol
347 #endif // !defined(USE_SERIAL_RX)
349 #if !defined(USE_TELEMETRY)
350 #define USE_TELEMETRY
352 #define USE_TELEMETRY_FRSKY_HUB
353 #define USE_TELEMETRY_SMARTPORT
354 #define USE_TELEMETRY_CRSF
355 #define USE_TELEMETRY_GHST
356 #define USE_TELEMETRY_SRXL
358 #endif // !defined(USE_TELEMETRY)
360 #define USE_SERVOS
362 #define USE_VTX
363 #define USE_OSD
364 #define USE_OSD_SD
365 #define USE_OSD_HD
366 #define USE_BLACKBOX
368 #if TARGET_FLASH_SIZE > 512
370 #if defined(USE_SERIALRX)
372 #define USE_SERIALRX_JETIEXBUS
373 #define USE_SERIALRX_SUMD // Graupner Hott protocol
374 #define USE_SERIALRX_SUMH // Graupner legacy protocol
376 #endif // USE_SERIALRX
378 #if defined(USE_TELEMETRY)
380 #define USE_TELEMETRY_IBUS
381 #define USE_TELEMETRY_IBUS_EXTENDED
382 #define USE_TELEMETRY_JETIEXBUS
383 #define USE_TELEMETRY_MAVLINK
384 #define USE_TELEMETRY_HOTT
385 #define USE_TELEMETRY_LTM
387 #endif // USE_TELEMETRY
389 #define USE_BATTERY_CONTINUE
390 #define USE_DASHBOARD
391 #define USE_EMFAT_AUTORUN
392 #define USE_EMFAT_ICON
393 #define USE_ESCSERIAL_SIMONK
394 #define USE_GPS
395 #define USE_GPS_PLUS_CODES
396 #define USE_LED_STRIP
397 #define USE_SERIAL_4WAY_SK_BOOTLOADER
398 #endif
400 #endif // !defined(CLOUD_BUILD)
402 #if !defined(LED_MAX_STRIP_LENGTH)
403 #ifdef USE_LEDSTRIP_64
404 #define LED_MAX_STRIP_LENGTH 64
405 #else
406 #define LED_MAX_STRIP_LENGTH 32
407 #endif
408 #endif // # !defined(LED_MAX_STRIP_LENGTH)
410 #if defined(USE_LED_STRIP)
411 #define USE_LED_STRIP_STATUS_MODE
412 #endif
414 #if defined(USE_SDCARD)
415 #define USE_SDCARD_SPI
416 #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
417 #define USE_SDCARD_SDIO
418 #endif
419 #endif
421 #if (defined(USE_SDCARD) || defined(USE_FLASH)) && !defined(USE_BLACKBOX)
422 #define USE_BLACKBOX
423 #endif
425 #if defined(USE_PINIO)
426 #define USE_PINIOBOX
427 #define USE_PIN_PULL_UP_DOWN
428 #endif
430 #if defined(USE_VTX)
431 #define USE_VTX_COMMON
432 #define USE_VTX_CONTROL
433 #define USE_VTX_SMARTAUDIO
434 #define USE_VTX_TRAMP
435 #define USE_VTX_MSP
436 #define USE_VTX_TABLE
437 #endif // USE_VTX
439 #define USE_HUFFMAN
441 #define PID_PROFILE_COUNT 4
442 #define CONTROL_RATE_PROFILE_COUNT 4
444 #define USE_CLI_BATCH
445 #define USE_RESOURCE_MGMT
447 #define USE_RUNAWAY_TAKEOFF // Runaway Takeoff Prevention (anti-taz)
449 #define USE_GYRO_OVERFLOW_CHECK
450 #define USE_YAW_SPIN_RECOVERY
452 #ifdef USE_DSHOT
453 #define USE_DSHOT_DMAR
454 #endif
456 #define USE_MSP_OVER_TELEMETRY
458 #define USE_VIRTUAL_CURRENT_METER
459 #define USE_ESC_SENSOR
460 #define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
461 #define USE_RCDEVICE
463 #define USE_GYRO_LPF2
464 #define USE_DYN_LPF
465 #define USE_D_MIN
467 #define USE_THROTTLE_BOOST
468 #define USE_INTEGRATED_YAW_CONTROL
470 #define USE_ITERM_RELAX
471 #define USE_RC_SMOOTHING_FILTER
472 #define USE_THRUST_LINEARIZATION
473 #define USE_TPA_MODE
475 #ifdef USE_SERIALRX_SPEKTRUM
476 #define USE_SPEKTRUM_BIND
477 #define USE_SPEKTRUM_BIND_PLUG
478 #define USE_SPEKTRUM_REAL_RSSI
479 #define USE_SPEKTRUM_FAKE_RSSI
480 #define USE_SPEKTRUM_RSSI_PERCENT_CONVERSION
481 #define USE_SPEKTRUM_VTX_CONTROL
482 #define USE_SPEKTRUM_VTX_TELEMETRY
483 #define USE_SPEKTRUM_CMS_TELEMETRY
484 #endif // USE_SERIALRX_SPEKTRUM
486 #define USE_BOARD_INFO
487 #define USE_RTC_TIME
488 #define USE_ESC_SENSOR_INFO
490 #define USE_RX_MSP
491 #define USE_RX_RSSI_DBM
492 #define USE_RX_RSNR
493 #define USE_RX_LINK_QUALITY_INFO
494 #define USE_RX_MSP_OVERRIDE
495 #define USE_RX_LINK_UPLINK_POWER
497 #define USE_AIRMODE_LPF
498 #define USE_GYRO_DLPF_EXPERIMENTAL
499 #define USE_MULTI_GYRO
500 #define USE_SENSOR_NAMES
501 #define USE_UNCOMMON_MIXERS
502 #define USE_SIGNATURE
503 #define USE_ABSOLUTE_CONTROL
504 #define USE_HOTT_TEXTMODE
505 #define USE_ESC_SENSOR_TELEMETRY
506 #define USE_TELEMETRY_SENSORS_DISABLED_DETAILS
507 #define USE_PERSISTENT_STATS
508 #define USE_PROFILE_NAMES
509 #define USE_FEEDFORWARD
510 #define USE_CUSTOM_BOX_NAMES
511 #define USE_BATTERY_VOLTAGE_SAG_COMPENSATION
512 #define USE_SIMPLIFIED_TUNING
513 #define USE_CRAFTNAME_MSGS
516 #ifdef USE_GPS
517 #define USE_GPS_NMEA
518 #define USE_GPS_UBLOX
519 #define USE_GPS_RESCUE
520 #endif // USE_GPS
523 #if (defined(USE_OSD_HD) || defined(USE_OSD_SD)) && !defined(USE_OSD)
524 // If either USE_OSD_SD for USE_OSD_HD are defined, ensure that USE_OSD is also defined
525 #define USE_OSD
526 #endif
529 #if defined(USE_OSD)
531 #if !defined(USE_OSD_HD) && !defined(USE_OSD_SD)
532 // If USE_OSD is defined without specifying SD or HD, then support both
533 #define USE_OSD_SD
534 #define USE_OSD_HD
535 #endif
537 #if !defined(USE_OSD_SD) && defined(USE_MAX7456)
538 // If USE_OSD_SD isn't defined then explicitly exclude MAX7456 support
539 #undef USE_MAX7456
540 #endif
542 #define USE_CANVAS
543 #define USE_CMS
544 #define USE_CMS_FAILSAFE_MENU
545 #define USE_EXTENDED_CMS_MENUS
546 #define USE_MSP_DISPLAYPORT
547 #define USE_OSD_OVER_MSP_DISPLAYPORT
548 #define USE_OSD_ADJUSTMENTS
549 #define USE_OSD_PROFILES
550 #define USE_OSD_STICK_OVERLAY
552 #if defined(USE_GPS)
553 #define USE_CMS_GPS_RESCUE_MENU
554 #endif
556 #endif // defined(USE_OSD)
559 #if defined(USE_SERIALRX_CRSF)
561 #define USE_CRSF_V3
563 #if defined(USE_TELEMETRY_CRSF) && defined(USE_CMS)
564 #define USE_CRSF_CMS_TELEMETRY
565 #define USE_CRSF_LINK_STATISTICS
566 #endif
568 #endif // defined(USE_SERIALRX_CRSF)