duplicate emptyline removal (#14027)
[betaflight.git] / src / main / target / common_post.h
blob6355f2fe94e7e79e0ed62e2c1ea6e5767462d609
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 #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
29 has been processed.
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
44 #else
45 #define DEFAULT_AUX_CHANNEL_COUNT 6
46 #endif
48 #ifdef USE_ITCM_RAM
49 #if defined(ITCM_RAM_OPTIMISATION) && !defined(DEBUG)
50 #define FAST_CODE __attribute__((section(".tcm_code"))) __attribute__((optimize(ITCM_RAM_OPTIMISATION)))
51 #else
52 #define FAST_CODE __attribute__((section(".tcm_code")))
53 #endif
54 // Handle case where we'd prefer code to be in ITCM, but it won't fit on the device
55 #ifndef FAST_CODE_PREF
56 #define FAST_CODE_PREF FAST_CODE
57 #endif
59 #define FAST_CODE_NOINLINE NOINLINE
61 #else
62 #define FAST_CODE
63 #define FAST_CODE_PREF
64 #define FAST_CODE_NOINLINE
65 #endif // USE_ITCM_RAM
67 #ifdef USE_CCM_CODE
68 #define CCM_CODE __attribute__((section(".ccm_code")))
69 #else
70 #define CCM_CODE
71 #endif
73 #ifdef USE_FAST_DATA
74 #define FAST_DATA_ZERO_INIT __attribute__ ((section(".fastram_bss"), aligned(4)))
75 #define FAST_DATA __attribute__ ((section(".fastram_data"), aligned(4)))
76 #else
77 #define FAST_DATA_ZERO_INIT
78 #define FAST_DATA
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 // normalize serial ports definitions
89 #include "serial_post.h"
91 #if defined(USE_MAG) && !defined(USE_VIRTUAL_MAG)
93 #ifndef USE_MAG_DATA_READY_SIGNAL
94 #define USE_MAG_DATA_READY_SIGNAL
95 #endif
96 #ifndef USE_MAG_HMC5883
97 #define USE_MAG_HMC5883
98 #endif
99 #ifndef USE_MAG_SPI_HMC5883
100 #define USE_MAG_SPI_HMC5883
101 #endif
102 #ifndef USE_MAG_QMC5883
103 #define USE_MAG_QMC5883
104 #endif
105 #ifndef USE_MAG_LIS2MDL
106 #define USE_MAG_LIS2MDL
107 #endif
108 #ifndef USE_MAG_LIS3MDL
109 #define USE_MAG_LIS3MDL
110 #endif
111 #ifndef USE_MAG_AK8963
112 #define USE_MAG_AK8963
113 #endif
114 #ifndef USE_MAG_MPU925X_AK8963
115 #define USE_MAG_MPU925X_AK8963
116 #endif
117 #ifndef USE_MAG_SPI_AK8963
118 #define USE_MAG_SPI_AK8963
119 #endif
120 #ifndef USE_MAG_AK8975
121 #define USE_MAG_AK8975
122 #endif
123 #ifndef USE_MAG_IST8310
124 #define USE_MAG_IST8310
125 #endif
127 #endif // END MAG HW defines
129 #if defined(USE_RX_CC2500)
131 #if !defined(USE_RX_SPI)
132 #define USE_RX_SPI
133 #endif
135 #define USE_RX_CC2500_SPI_PA_LNA
136 #define USE_RX_CC2500_SPI_DIVERSITY
138 #define USE_RX_SFHSS_SPI
139 #define USE_RX_REDPINE_SPI
141 #define USE_RX_FRSKY_SPI_D
142 #define USE_RX_FRSKY_SPI_X
143 #define USE_RX_FRSKY_SPI
144 #define USE_RX_FRSKY_SPI_TELEMETRY
146 #define USE_RX_FLYSKY
147 #define USE_RX_FLYSKY_SPI_LED
148 #define USE_RX_SPEKTRUM
149 #define USE_RX_SPEKTRUM_TELEMETRY
151 #endif // defined(USE_RX_CC2500)
153 #if defined(CAMERA_CONTROL_PIN) && defined(USE_VTX) && !defined(USE_CAMERA_CONTROL)
154 #define USE_CAMERA_CONTROL
155 #endif
157 /* END HARDWARE INCLUSIONS */
159 #if defined(USE_VTX_RTC6705_SOFTSPI)
160 #define USE_VTX_RTC6705
161 #endif
163 #ifndef USE_DSHOT
164 #undef USE_ESC_SENSOR
165 #endif
167 #ifndef USE_ESC_SENSOR
168 #undef USE_ESC_SENSOR_TELEMETRY
169 #endif
171 // XXX Followup implicit dependencies among DASHBOARD, display_xxx and USE_I2C.
172 // XXX This should eventually be cleaned up.
173 #ifndef USE_I2C
174 #undef USE_I2C_OLED_DISPLAY
175 #undef USE_DASHBOARD
176 #else
177 #ifdef USE_DASHBOARD
178 #define USE_I2C_OLED_DISPLAY
179 #endif
180 #endif
182 // Remove USE_BARO_BMP280 and USE_BARO_MS5611 if USE_I2C is not defined.
183 #if !defined(USE_I2C)
184 #if defined(USE_BARO_BMP280)
185 #undef USE_BARO_BMP280
186 #endif
187 #if defined(USE_BARO_MS5611)
188 #undef USE_BARO_MS5611
189 #endif
190 #endif
192 // Add VARIO if BARO or GPS is defined. Remove when none defined.
193 #if defined(USE_BARO) || defined(USE_GPS)
194 #ifndef USE_VARIO
195 #define USE_VARIO
196 #endif
197 #else
198 #undef USE_VARIO
199 #endif
201 #if !defined(USE_SERIALRX)
202 #undef USE_SERIALRX_CRSF
203 #undef USE_SERIALRX_GHST
204 #undef USE_SERIALRX_IBUS
205 #undef USE_SERIALRX_JETIEXBUS
206 #undef USE_SERIALRX_SBUS
207 #undef USE_SERIALRX_SPEKTRUM
208 #undef USE_SERIALRX_SUMD
209 #undef USE_SERIALRX_SUMH
210 #undef USE_SERIALRX_XBUS
211 #undef USE_SERIALRX_FPORT
212 #endif
214 #if !defined(USE_TELEMETRY)
215 #undef USE_TELEMETRY_CRSF
216 #undef USE_TELEMETRY_GHST
217 #undef USE_TELEMETRY_FRSKY_HUB
218 #undef USE_TELEMETRY_HOTT
219 #undef USE_TELEMETRY_IBUS
220 #undef USE_TELEMETRY_IBUS_EXTENDED
221 #undef USE_TELEMETRY_JETIEXBUS
222 #undef USE_TELEMETRY_LTM
223 #undef USE_TELEMETRY_MAVLINK
224 #undef USE_TELEMETRY_SMARTPORT
225 #undef USE_TELEMETRY_SRXL
226 #endif
228 #ifdef USE_SERIALRX_FPORT
229 #ifndef USE_TELEMETRY
230 #define USE_TELEMETRY
231 #endif
232 #ifndef USE_TELEMETRY_SMARTPORT
233 #define USE_TELEMETRY_SMARTPORT
234 #endif
235 #endif
237 #if defined(USE_TELEMETRY_IBUS_EXTENDED) && !defined(USE_TELEMETRY_IBUS)
238 #ifndef USE_TELEMETRY
239 #define USE_TELEMETRY
240 #endif
241 #define USE_TELEMETRY_IBUS
242 #endif
244 #ifdef USE_SERIALRX_JETIEXBUS
245 #ifndef USE_TELEMETRY
246 #define USE_TELEMETRY
247 #endif
248 #ifndef USE_TELEMETRY_JETIEXBUS
249 #define USE_TELEMETRY_JETIEXBUS
250 #endif
251 #endif // USE_SERIALRX_JETIEXBUS
253 #if !defined(USE_SERIALRX_CRSF)
254 #undef USE_TELEMETRY_CRSF
255 #undef USE_CRSF_LINK_STATISTICS
256 #undef USE_CRSF_V3
257 #endif
259 #if !defined(USE_RX_EXPRESSLRS) && !defined(USE_SERIALRX_CRSF)
260 #undef USE_RX_RSSI_DBM
261 #endif
263 #if !defined(USE_SERIALRX_GHST)
264 #undef USE_TELEMETRY_GHST
265 #endif
267 #if !defined(USE_TELEMETRY_CRSF) || !defined(USE_CMS)
268 #undef USE_CRSF_CMS_TELEMETRY
269 #endif
271 #if !defined(USE_TELEMETRY_CRSF)
272 #undef USE_CRSF_V3
273 #endif
275 #if !defined(USE_SERIALRX_JETIEXBUS)
276 #undef USE_TELEMETRY_JETIEXBUS
277 #endif
279 #if !defined(USE_TELEMETRY_IBUS)
280 #undef USE_TELEMETRY_IBUS_EXTENDED
281 #endif
283 // If USE_SERIALRX_SPEKTRUM or SERIALRX_SRXL2 was dropped by a target, drop all related options
284 #if !defined(USE_SERIALRX_SPEKTRUM) && !defined(USE_SERIALRX_SRXL2)
285 #undef USE_SPEKTRUM_BIND
286 #undef USE_SPEKTRUM_BIND_PLUG
287 #undef USE_SPEKTRUM_REAL_RSSI
288 #undef USE_SPEKTRUM_VIRTUAL_RSSI
289 #undef USE_SPEKTRUM_RSSI_PERCENT_CONVERSION
290 #undef USE_SPEKTRUM_VTX_CONTROL
291 #undef USE_SPEKTRUM_VTX_TELEMETRY
292 #undef USE_TELEMETRY_SRXL
293 #endif // !defined(USE_SERIALRX_SPEKTRUM) && !defined(USE_SERIALRX_SRXL2)
295 #if !defined(USE_CMS) || !defined(USE_TELEMETRY_SRXL)
296 #undef USE_SPEKTRUM_CMS_TELEMETRY
297 #endif
299 #if defined(USE_SERIALRX_SBUS) || defined(USE_SERIALRX_FPORT)
300 #if !defined(USE_SBUS_CHANNELS)
301 #define USE_SBUS_CHANNELS
302 #endif
303 #endif
305 #if !defined(USE_TELEMETRY_SMARTPORT) && !defined(USE_TELEMETRY_CRSF) && !defined(USE_TELEMETRY_GHST)
306 #undef USE_MSP_OVER_TELEMETRY
307 #endif
309 #if !defined(USE_RX_MSP) && defined(USE_RX_MSP_OVERRIDE)
310 #undef USE_RX_MSP_OVERRIDE
311 #endif
313 /* If either VTX_CONTROL or VTX_COMMON is undefined then remove common code and device drivers */
314 #if !defined(USE_VTX_COMMON) || !defined(USE_VTX_CONTROL)
315 #undef USE_VTX_COMMON
316 #undef USE_VTX_CONTROL
317 #undef USE_VTX_TRAMP
318 #undef USE_VTX_SMARTAUDIO
319 #undef USE_VTX_TABLE
320 #undef USE_VTX_MSP
321 #endif
323 // Some target doesn't define USE_ADC which USE_ADC_INTERNAL depends on
324 #ifndef USE_ADC
325 #undef USE_ADC_INTERNAL
326 #endif
328 #if (defined(USE_SDCARD) || defined(USE_FLASH)) && !defined(USE_BLACKBOX)
329 #define USE_BLACKBOX
330 #endif
332 #ifdef USE_FLASH
333 #if !defined(USE_FLASH_TOOLS)
334 #define USE_FLASH_TOOLS
335 #endif
336 #if !defined(USE_FLASHFS)
337 #define USE_FLASHFS
338 #endif
339 #endif
341 #if (defined(USE_FLASH_W25M512) || defined(USE_FLASH_W25Q128FV) || defined(USE_FLASH_PY25Q128HA)) && !defined(USE_FLASH_M25P16)
342 #define USE_FLASH_M25P16
343 #endif
345 #if defined(USE_FLASH_W25M02G) && !defined(USE_FLASH_W25N01G)
346 #define USE_FLASH_W25N01G
347 #endif
349 #if defined(USE_FLASH_W25N02K) || defined(USE_FLASH_W25N01G)
350 #define USE_FLASH_W25N
351 #endif
353 #if (defined(USE_FLASH_M25P16) || defined(USE_FLASH_W25N)) && !defined(USE_FLASH_W25M)
354 #define USE_FLASH_W25M
355 #endif
357 #if defined(USE_FLASH_M25P16) || defined(USE_FLASH_W25M) || defined(USE_FLASH_W25N) || defined(USE_FLASH_W25Q128FV)
358 #if !defined(USE_FLASH_CHIP)
359 #define USE_FLASH_CHIP
360 #endif
361 #endif
363 #if defined(USE_SPI) && (defined(USE_FLASH_M25P16) || defined(USE_FLASH_W25M512) || defined(USE_FLASH_W25N) || defined(USE_FLASH_W25M02G))
364 #if !defined(USE_FLASH_SPI)
365 #define USE_FLASH_SPI
366 #endif
367 #endif
369 #if defined(USE_QUADSPI) && (defined(USE_FLASH_W25Q128FV) || defined(USE_FLASH_W25N))
370 #if !defined(USE_FLASH_QUADSPI)
371 #define USE_FLASH_QUADSPI
372 #endif
373 #endif
375 #if defined(USE_OCTOSPI) && defined(USE_FLASH_W25Q128FV)
376 #if !defined(USE_FLASH_OCTOSPI)
377 #define USE_FLASH_OCTOSPI
378 #endif
379 #endif
381 #ifndef USE_FLASH_CHIP
382 #undef USE_FLASH_TOOLS
383 #undef USE_FLASHFS
384 #endif
386 #if (!defined(USE_SDCARD) && !defined(USE_FLASHFS)) || !defined(USE_BLACKBOX)
387 #undef USE_USB_MSC
388 #endif
390 #if !defined(USE_SDCARD)
391 #undef USE_SDCARD_SDIO
392 #undef USE_SDCARD_SPI
393 #endif
395 #if !defined(USE_VCP)
396 #undef USE_USB_CDC_HID
397 #undef USE_USB_MSC
398 #endif
400 #if defined(USE_USB_CDC_HID) || defined(USE_USB_MSC)
401 #define USE_USB_ADVANCED_PROFILES
402 #endif
404 #if !defined(USE_OSD)
405 #undef USE_RX_LINK_QUALITY_INFO
406 #undef USE_OSD_PROFILES
407 #undef USE_OSD_STICK_OVERLAY
408 #undef USE_RX_LINK_UPLINK_POWER
409 #endif
411 // Older ACC/GYRO sensors use MPU6500 driver
412 #if !defined(USE_ACC_MPU6500) && (defined(USE_ACC_ICM20601) || defined(USE_ACC_ICM20602) || defined(USE_ACC_ICM20608G))
413 #define USE_ACC_MPU6500
414 #endif
415 #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))
416 #define USE_ACC_SPI_MPU6500
417 #endif
418 #if !defined(USE_GYRO_MPU6500) && (defined(USE_GYRO_ICM20601) || defined(USE_GYRO_ICM20602) || defined(USE_GYRO_ICM20608G))
419 #define USE_GYRO_MPU6500
420 #endif
421 #if !defined(USE_GYRO_SPI_MPU6500) && (defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20602) || defined(USE_GYRO_SPI_ICM20608G))
422 #define USE_GYRO_SPI_MPU6500
423 #endif
425 // Generate USE_SPI_GYRO or USE_I2C_GYRO
426 #if defined(USE_GYRO_L3G4200D) || defined(USE_GYRO_MPU3050) || defined(USE_GYRO_MPU6000) || defined(USE_GYRO_MPU6050) || defined(USE_GYRO_MPU6500)
427 #ifndef USE_I2C_GYRO
428 #define USE_I2C_GYRO
429 #endif
430 #endif
432 #if defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU9250) \
433 || defined(USE_GYRO_L3GD20) || defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) || defined(USE_ACCGYRO_BMI160) \
434 || defined(USE_ACCGYRO_BMI270) || defined(USE_ACCGYRO_LSM6DSV16X) || defined(USE_ACCGYRO_LSM6DSO)
435 #ifndef USE_SPI_GYRO
436 #define USE_SPI_GYRO
437 #endif
438 #endif
440 #ifndef SIMULATOR_BUILD
441 #ifndef USE_ACC
442 #define USE_ACC
443 #endif
445 #ifndef USE_GYRO
446 #define USE_GYRO
447 #endif
448 #endif
450 // CX10 is a special case of SPI RX which requires XN297
451 #if defined(USE_RX_CX10)
452 #define USE_RX_XN297
453 #endif
455 // Setup crystal frequency on F4 for backward compatibility
456 // Should be set to zero for generic targets to ensure USB is working
457 // when unconfigured for targets with non-standard crystal.
458 // Can be set at runtime with with CLI parameter 'system_hse_mhz'.
459 #ifndef SYSTEM_HSE_MHZ
460 #define SYSTEM_HSE_MHZ 0
461 #endif
463 // Number of pins that needs pre-init
464 #ifdef USE_SPI
465 #ifndef SPI_PREINIT_COUNT
466 // 2 x 8 (GYROx2, BARO, MAG, MAX, FLASHx2, RX)
467 #define SPI_PREINIT_COUNT 16
468 #endif
469 #endif
471 #ifndef USE_BLACKBOX
472 #undef USE_USB_MSC
473 #endif
475 #if (!defined(USE_FLASHFS) || !defined(USE_RTC_TIME) || !defined(USE_USB_MSC) || !defined(USE_PERSISTENT_OBJECTS))
476 #undef USE_PERSISTENT_MSC_RTC
477 #endif
479 #if !defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) && !defined(USE_SERIAL_4WAY_SK_BOOTLOADER)
480 #undef USE_SERIAL_4WAY_BLHELI_INTERFACE
481 #elif !defined(USE_SERIAL_4WAY_BLHELI_INTERFACE) && (defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) || defined(USE_SERIAL_4WAY_SK_BOOTLOADER))
482 #ifndef USE_SERIAL_4WAY_BLHELI_INTERFACE
483 #define USE_SERIAL_4WAY_BLHELI_INTERFACE
484 #endif
485 #endif
487 #if defined(USE_RX_PWM) || defined(USE_DSHOT) || defined(USE_LED_STRIP) || defined(USE_TRANSPONDER) || defined(USE_BEEPER) || defined(USE_SERIAL_4WAY_BLHELI_INTERFACE)
488 #ifndef USE_PWM_OUTPUT
489 #define USE_PWM_OUTPUT
490 #endif
491 #endif
493 #if !defined(USE_LED_STRIP)
494 #undef USE_LED_STRIP_STATUS_MODE
495 #endif
497 #if defined(USE_MAX7456) || defined(USE_FRSKYOSD) || defined(USE_MSP_DISPLAYPORT)
498 #ifndef USE_VIDEO_SYSTEM
499 #define USE_VIDEO_SYSTEM
500 #endif
501 #endif
503 #if defined(USE_LED_STRIP) && !defined(USE_LED_STRIP_STATUS_MODE)
504 #define USE_WS2811_SINGLE_COLOUR
505 #endif
507 #if defined(SIMULATOR_BUILD) || defined(UNIT_TEST)
508 // This feature uses 'arm_math.h', which does not exist for x86.
509 #undef USE_DYN_NOTCH_FILTER
510 #endif
512 #ifndef USE_CMS
513 #undef USE_CMS_FAILSAFE_MENU
514 #endif
516 #ifndef USE_DSHOT
517 #undef USE_DSHOT_TELEMETRY
518 #undef USE_DSHOT_BITBANG
519 #endif
521 #ifndef USE_DSHOT_TELEMETRY
522 #undef USE_RPM_FILTER
523 #undef USE_DSHOT_TELEMETRY_STATS
524 #undef USE_DYN_IDLE
525 #endif
527 #if !defined(USE_BOARD_INFO)
528 #undef USE_SIGNATURE
529 #endif
531 #if !defined(USE_ACC)
532 #undef USE_GPS_RESCUE
533 #undef USE_ACRO_TRAINER
534 #endif
536 #if (!defined(USE_GPS_RESCUE) || !defined(USE_CMS_FAILSAFE_MENU))
537 #undef USE_CMS_GPS_RESCUE_MENU
538 #endif
540 #ifndef USE_BEEPER
541 #undef BEEPER_PIN
542 #undef BEEPER_PWM_HZ
543 #endif
545 #if defined(USE_DMA_SPEC)
546 #define USE_TIMER_DMA
547 #else
548 #undef USE_TIMER_MGMT
549 #endif
551 #if defined(USE_TIMER_MGMT)
552 #undef USED_TIMERS
553 #endif
555 #if !defined(USE_RANGEFINDER)
556 #undef USE_RANGEFINDER_HCSR04
557 #undef USE_RANGEFINDER_SRF10
558 #undef USE_RANGEFINDER_HCSR04_I2C
559 #undef USE_RANGEFINDER_VL53L0X
560 #undef USE_RANGEFINDER_UIB
561 #undef USE_RANGEFINDER_TF
562 #endif
564 #ifndef USE_GPS_RESCUE
565 #undef USE_CMS_GPS_RESCUE_MENU
566 #endif
568 #if defined(CONFIG_IN_RAM) || defined(CONFIG_IN_FILE) || defined(CONFIG_IN_EXTERNAL_FLASH) || defined(CONFIG_IN_SDCARD) || defined(CONFIG_IN_MEMORY_MAPPED_FLASH)
569 #ifndef EEPROM_SIZE
570 #define EEPROM_SIZE 4096
571 #endif
572 extern uint8_t eepromData[EEPROM_SIZE];
573 #define __config_start (*eepromData)
574 #define __config_end (*ARRAYEND(eepromData))
575 #else
576 #ifndef CONFIG_IN_FLASH
577 #define CONFIG_IN_FLASH
578 #endif
579 extern uint8_t __config_start; // configured via linker script when building binaries.
580 extern uint8_t __config_end;
581 #endif
583 #if defined(USE_EXST) && !defined(RAMBASED)
584 #define USE_FLASH_BOOT_LOADER
585 #endif
587 #if defined(USE_FLASH_MEMORY_MAPPED)
588 #if !defined(USE_RAM_CODE)
589 #define USE_RAM_CODE
590 #endif
592 #define MMFLASH_CODE RAM_CODE
593 #define MMFLASH_CODE_NOINLINE RAM_CODE NOINLINE
595 #define MMFLASH_DATA FAST_DATA
596 #define MMFLASH_DATA_ZERO_INIT FAST_DATA_ZERO_INIT
597 #else
598 #define MMFLASH_CODE
599 #define MMFLASH_CODE_NOINLINE
600 #define MMFLASH_DATA
601 #define MMFLASH_DATA_ZERO_INIT
602 #endif
604 #ifdef USE_RAM_CODE
605 // RAM_CODE for methods that need to be in RAM, but don't need to be in the fastest type of memory.
606 // 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
607 #define RAM_CODE __attribute__((section(".ram_code")))
608 #endif
610 #ifndef USE_ITERM_RELAX
611 #undef USE_ABSOLUTE_CONTROL
612 #endif
614 #if defined(USE_RX_EXPRESSLRS)
615 // ELRS depends on CRSF telemetry
616 #if !defined(USE_TELEMETRY)
617 #define USE_TELEMETRY
618 #endif
619 #if !defined(USE_TELEMETRY_CRSF)
620 #define USE_TELEMETRY_CRSF
621 #endif
622 #if !defined(USE_CRSF_LINK_STATISTICS)
623 #define USE_CRSF_LINK_STATISTICS
624 #endif
625 #if !defined(USE_SERIALRX_CRSF)
626 #define USE_SERIALRX_CRSF
627 #endif
628 #endif
630 #if defined(USE_RX_SPI) || defined(USE_SERIALRX_SRXL2) || defined(USE_SERIALRX_CRSF)
631 #define USE_RX_BIND
632 #endif
634 #ifndef USE_GPS
635 #undef USE_GPS_PLUS_CODES
636 #undef USE_GPS_LAP_TIMER
637 #endif
639 #ifdef USE_GPS_LAP_TIMER
640 #define USE_CMS_GPS_LAP_TIMER_MENU
641 #endif
643 // Enable PINIO by default if any PIN is defined
644 #if !defined(USE_PINIO) && (defined(PINIO1_BOX) || defined(PINIO2_BOX) || defined(PINIO3_BOX) || defined(PINIO4_BOX))
645 #define USE_PINIO
646 #endif
648 #ifdef USE_PINIO
649 #ifndef USE_PINIOBOX
650 #define USE_PINIOBOX
651 #endif
652 #ifndef USE_PIN_PULL_UP_DOWN
653 #define USE_PIN_PULL_UP_DOWN
654 #endif
655 #endif // USE_PINIO