Fix flash_scan (#13789)
[betaflight.git] / src / main / target / common_post.h
blobfc901e38279a29e0d694b990caccb8c48f4c912a
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 #if defined(USE_MAG) && !defined(USE_VIRTUAL_MAG)
90 #ifndef USE_MAG_DATA_READY_SIGNAL
91 #define USE_MAG_DATA_READY_SIGNAL
92 #endif
93 #ifndef USE_MAG_HMC5883
94 #define USE_MAG_HMC5883
95 #endif
96 #ifndef USE_MAG_SPI_HMC5883
97 #define USE_MAG_SPI_HMC5883
98 #endif
99 #ifndef USE_MAG_QMC5883
100 #define USE_MAG_QMC5883
101 #endif
102 #ifndef USE_MAG_LIS2MDL
103 #define USE_MAG_LIS2MDL
104 #endif
105 #ifndef USE_MAG_LIS3MDL
106 #define USE_MAG_LIS3MDL
107 #endif
108 #ifndef USE_MAG_AK8963
109 #define USE_MAG_AK8963
110 #endif
111 #ifndef USE_MAG_MPU925X_AK8963
112 #define USE_MAG_MPU925X_AK8963
113 #endif
114 #ifndef USE_MAG_SPI_AK8963
115 #define USE_MAG_SPI_AK8963
116 #endif
117 #ifndef USE_MAG_AK8975
118 #define USE_MAG_AK8975
119 #endif
120 #ifndef USE_MAG_IST8310
121 #define USE_MAG_IST8310
122 #endif
124 #endif // END MAG HW defines
126 #if defined(USE_RX_CC2500)
128 #if !defined(USE_RX_SPI)
129 #define USE_RX_SPI
130 #endif
132 #define USE_RX_CC2500_SPI_PA_LNA
133 #define USE_RX_CC2500_SPI_DIVERSITY
135 #define USE_RX_SFHSS_SPI
136 #define USE_RX_REDPINE_SPI
138 #define USE_RX_FRSKY_SPI_D
139 #define USE_RX_FRSKY_SPI_X
140 #define USE_RX_FRSKY_SPI
141 #define USE_RX_FRSKY_SPI_TELEMETRY
143 #define USE_RX_FLYSKY
144 #define USE_RX_FLYSKY_SPI_LED
145 #define USE_RX_SPEKTRUM
146 #define USE_RX_SPEKTRUM_TELEMETRY
148 #endif // defined(USE_RX_CC2500)
150 #if defined(CAMERA_CONTROL_PIN) && defined(USE_VTX) && !defined(USE_CAMERA_CONTROL)
151 #define USE_CAMERA_CONTROL
152 #endif
154 /* END HARDWARE INCLUSIONS */
156 #if defined(USE_VTX_RTC6705_SOFTSPI)
157 #define USE_VTX_RTC6705
158 #endif
160 #ifndef USE_DSHOT
161 #undef USE_ESC_SENSOR
162 #endif
164 #ifndef USE_ESC_SENSOR
165 #undef USE_ESC_SENSOR_TELEMETRY
166 #endif
168 // XXX Followup implicit dependencies among DASHBOARD, display_xxx and USE_I2C.
169 // XXX This should eventually be cleaned up.
170 #ifndef USE_I2C
171 #undef USE_I2C_OLED_DISPLAY
172 #undef USE_DASHBOARD
173 #else
174 #ifdef USE_DASHBOARD
175 #define USE_I2C_OLED_DISPLAY
176 #endif
177 #endif
179 // Remove USE_BARO_BMP280 and USE_BARO_MS5611 if USE_I2C is not defined.
180 #if !defined(USE_I2C)
181 #if defined(USE_BARO_BMP280)
182 #undef USE_BARO_BMP280
183 #endif
184 #if defined(USE_BARO_MS5611)
185 #undef USE_BARO_MS5611
186 #endif
187 #endif
189 // Add VARIO if BARO or GPS is defined. Remove when none defined.
190 #if defined(USE_BARO) || defined(USE_GPS)
191 #ifndef USE_VARIO
192 #define USE_VARIO
193 #endif
194 #else
195 #undef USE_VARIO
196 #endif
198 #if !defined(USE_SERIALRX)
199 #undef USE_SERIALRX_CRSF
200 #undef USE_SERIALRX_GHST
201 #undef USE_SERIALRX_IBUS
202 #undef USE_SERIALRX_JETIEXBUS
203 #undef USE_SERIALRX_SBUS
204 #undef USE_SERIALRX_SPEKTRUM
205 #undef USE_SERIALRX_SUMD
206 #undef USE_SERIALRX_SUMH
207 #undef USE_SERIALRX_XBUS
208 #undef USE_SERIALRX_FPORT
209 #endif
211 #if !defined(USE_TELEMETRY)
212 #undef USE_TELEMETRY_CRSF
213 #undef USE_TELEMETRY_GHST
214 #undef USE_TELEMETRY_FRSKY_HUB
215 #undef USE_TELEMETRY_HOTT
216 #undef USE_TELEMETRY_IBUS
217 #undef USE_TELEMETRY_IBUS_EXTENDED
218 #undef USE_TELEMETRY_JETIEXBUS
219 #undef USE_TELEMETRY_LTM
220 #undef USE_TELEMETRY_MAVLINK
221 #undef USE_TELEMETRY_SMARTPORT
222 #undef USE_TELEMETRY_SRXL
223 #endif
225 #ifdef USE_SERIALRX_FPORT
226 #ifndef USE_TELEMETRY
227 #define USE_TELEMETRY
228 #endif
229 #ifndef USE_TELEMETRY_SMARTPORT
230 #define USE_TELEMETRY_SMARTPORT
231 #endif
232 #endif
234 #if defined(USE_TELEMETRY_IBUS_EXTENDED) && !defined(USE_TELEMETRY_IBUS)
235 #define USE_TELEMETRY_IBUS
236 #endif
238 #if !defined(USE_SERIALRX_CRSF)
239 #undef USE_TELEMETRY_CRSF
240 #undef USE_CRSF_LINK_STATISTICS
241 #undef USE_CRSF_V3
242 #endif
244 #if !defined(USE_RX_EXPRESSLRS) && !defined(USE_SERIALRX_CRSF)
245 #undef USE_RX_RSSI_DBM
246 #endif
248 #if !defined(USE_SERIALRX_GHST)
249 #undef USE_TELEMETRY_GHST
250 #endif
252 #if !defined(USE_TELEMETRY_CRSF) || !defined(USE_CMS)
253 #undef USE_CRSF_CMS_TELEMETRY
254 #endif
256 #if !defined(USE_TELEMETRY_CRSF)
257 #undef USE_CRSF_V3
258 #endif
260 #if !defined(USE_SERIALRX_JETIEXBUS)
261 #undef USE_TELEMETRY_JETIEXBUS
262 #endif
264 #if !defined(USE_TELEMETRY_IBUS)
265 #undef USE_TELEMETRY_IBUS_EXTENDED
266 #endif
268 // If USE_SERIALRX_SPEKTRUM was dropped by a target, drop all related options
269 #ifndef USE_SERIALRX_SPEKTRUM
270 #undef USE_SPEKTRUM_BIND
271 #undef USE_SPEKTRUM_BIND_PLUG
272 #undef USE_SPEKTRUM_REAL_RSSI
273 #undef USE_SPEKTRUM_VIRTUAL_RSSI
274 #undef USE_SPEKTRUM_RSSI_PERCENT_CONVERSION
275 #undef USE_SPEKTRUM_VTX_CONTROL
276 #undef USE_SPEKTRUM_VTX_TELEMETRY
277 #undef USE_TELEMETRY_SRXL
278 #endif
280 #if !defined(USE_CMS) || !defined(USE_TELEMETRY_SRXL)
281 #undef USE_SPEKTRUM_CMS_TELEMETRY
282 #endif
284 #if defined(USE_SERIALRX_SBUS) || defined(USE_SERIALRX_FPORT)
285 #if !defined(USE_SBUS_CHANNELS)
286 #define USE_SBUS_CHANNELS
287 #endif
288 #endif
290 #if !defined(USE_TELEMETRY_SMARTPORT) && !defined(USE_TELEMETRY_CRSF) && !defined(USE_TELEMETRY_GHST)
291 #undef USE_MSP_OVER_TELEMETRY
292 #endif
294 #if !defined(USE_RX_MSP) && defined(USE_RX_MSP_OVERRIDE)
295 #undef USE_RX_MSP_OVERRIDE
296 #endif
298 /* If either VTX_CONTROL or VTX_COMMON is undefined then remove common code and device drivers */
299 #if !defined(USE_VTX_COMMON) || !defined(USE_VTX_CONTROL)
300 #undef USE_VTX_COMMON
301 #undef USE_VTX_CONTROL
302 #undef USE_VTX_TRAMP
303 #undef USE_VTX_SMARTAUDIO
304 #undef USE_VTX_TABLE
305 #undef USE_VTX_MSP
306 #endif
308 // Some target doesn't define USE_ADC which USE_ADC_INTERNAL depends on
309 #ifndef USE_ADC
310 #undef USE_ADC_INTERNAL
311 #endif
313 #if (defined(USE_SDCARD) || defined(USE_FLASH)) && !defined(USE_BLACKBOX)
314 #define USE_BLACKBOX
315 #endif
317 #ifdef USE_FLASH
318 #if !defined(USE_FLASH_TOOLS)
319 #define USE_FLASH_TOOLS
320 #endif
321 #if !defined(USE_FLASHFS)
322 #define USE_FLASHFS
323 #endif
324 #endif
326 #if (defined(USE_FLASH_W25M512) || defined(USE_FLASH_W25Q128FV) || defined(USE_FLASH_PY25Q128HA)) && !defined(USE_FLASH_M25P16)
327 #define USE_FLASH_M25P16
328 #endif
330 #if defined(USE_FLASH_W25M02G) && !defined(USE_FLASH_W25N01G)
331 #define USE_FLASH_W25N01G
332 #endif
334 #if defined(USE_FLASH_W25N02K) || defined(USE_FLASH_W25N01G)
335 #define USE_FLASH_W25N
336 #endif
338 #if (defined(USE_FLASH_M25P16) || defined(USE_FLASH_W25N)) && !defined(USE_FLASH_W25M)
339 #define USE_FLASH_W25M
340 #endif
342 #if defined(USE_FLASH_M25P16) || defined(USE_FLASH_W25M) || defined(USE_FLASH_W25N) || defined(USE_FLASH_W25Q128FV)
343 #if !defined(USE_FLASH_CHIP)
344 #define USE_FLASH_CHIP
345 #endif
346 #endif
348 #if defined(USE_SPI) && (defined(USE_FLASH_M25P16) || defined(USE_FLASH_W25M512) || defined(USE_FLASH_W25N) || defined(USE_FLASH_W25M02G))
349 #if !defined(USE_FLASH_SPI)
350 #define USE_FLASH_SPI
351 #endif
352 #endif
354 #if defined(USE_QUADSPI) && (defined(USE_FLASH_W25Q128FV) || defined(USE_FLASH_W25N))
355 #if !defined(USE_FLASH_QUADSPI)
356 #define USE_FLASH_QUADSPI
357 #endif
358 #endif
360 #if defined(USE_OCTOSPI) && defined(USE_FLASH_W25Q128FV)
361 #if !defined(USE_FLASH_OCTOSPI)
362 #define USE_FLASH_OCTOSPI
363 #endif
364 #endif
366 #ifndef USE_FLASH_CHIP
367 #undef USE_FLASH_TOOLS
368 #undef USE_FLASHFS
369 #endif
371 #if (!defined(USE_SDCARD) && !defined(USE_FLASHFS)) || !defined(USE_BLACKBOX)
372 #undef USE_USB_MSC
373 #endif
375 #if !defined(USE_SDCARD)
376 #undef USE_SDCARD_SDIO
377 #undef USE_SDCARD_SPI
378 #endif
380 #if !defined(USE_VCP)
381 #undef USE_USB_CDC_HID
382 #undef USE_USB_MSC
383 #endif
385 #if defined(USE_USB_CDC_HID) || defined(USE_USB_MSC)
386 #define USE_USB_ADVANCED_PROFILES
387 #endif
389 #if !defined(USE_OSD)
390 #undef USE_RX_LINK_QUALITY_INFO
391 #undef USE_OSD_PROFILES
392 #undef USE_OSD_STICK_OVERLAY
393 #undef USE_RX_LINK_UPLINK_POWER
394 #endif
396 // Older ACC/GYRO sensors use MPU6500 driver
397 #if !defined(USE_ACC_MPU6500) && (defined(USE_ACC_ICM20601) || defined(USE_ACC_ICM20602) || defined(USE_ACC_ICM20608G))
398 #define USE_ACC_MPU6500
399 #endif
400 #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))
401 #define USE_ACC_SPI_MPU6500
402 #endif
403 #if !defined(USE_GYRO_MPU6500) && (defined(USE_GYRO_ICM20601) || defined(USE_GYRO_ICM20602) || defined(USE_GYRO_ICM20608G))
404 #define USE_GYRO_MPU6500
405 #endif
406 #if !defined(USE_GYRO_SPI_MPU6500) && (defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20602) || defined(USE_GYRO_SPI_ICM20608G))
407 #define USE_GYRO_SPI_MPU6500
408 #endif
410 // Generate USE_SPI_GYRO or USE_I2C_GYRO
411 #if defined(USE_GYRO_L3G4200D) || defined(USE_GYRO_MPU3050) || defined(USE_GYRO_MPU6000) || defined(USE_GYRO_MPU6050) || defined(USE_GYRO_MPU6500)
412 #ifndef USE_I2C_GYRO
413 #define USE_I2C_GYRO
414 #endif
415 #endif
417 #if defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU9250) \
418 || defined(USE_GYRO_L3GD20) || defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) || defined(USE_ACCGYRO_BMI160) \
419 || defined(USE_ACCGYRO_BMI270) || defined(USE_ACCGYRO_LSM6DSV16X) || defined(USE_ACCGYRO_LSM6DSO)
420 #ifndef USE_SPI_GYRO
421 #define USE_SPI_GYRO
422 #endif
423 #endif
425 #ifndef SIMULATOR_BUILD
426 #ifndef USE_ACC
427 #define USE_ACC
428 #endif
430 #ifndef USE_GYRO
431 #define USE_GYRO
432 #endif
433 #endif
435 // CX10 is a special case of SPI RX which requires XN297
436 #if defined(USE_RX_CX10)
437 #define USE_RX_XN297
438 #endif
440 // Setup crystal frequency on F4 for backward compatibility
441 // Should be set to zero for generic targets to ensure USB is working
442 // when unconfigured for targets with non-standard crystal.
443 // Can be set at runtime with with CLI parameter 'system_hse_mhz'.
444 #ifndef SYSTEM_HSE_MHZ
445 #define SYSTEM_HSE_MHZ 0
446 #endif
448 // Number of pins that needs pre-init
449 #ifdef USE_SPI
450 #ifndef SPI_PREINIT_COUNT
451 // 2 x 8 (GYROx2, BARO, MAG, MAX, FLASHx2, RX)
452 #define SPI_PREINIT_COUNT 16
453 #endif
454 #endif
456 #ifndef USE_BLACKBOX
457 #undef USE_USB_MSC
458 #endif
460 #if (!defined(USE_FLASHFS) || !defined(USE_RTC_TIME) || !defined(USE_USB_MSC) || !defined(USE_PERSISTENT_OBJECTS))
461 #undef USE_PERSISTENT_MSC_RTC
462 #endif
464 #if !defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) && !defined(USE_SERIAL_4WAY_SK_BOOTLOADER)
465 #undef USE_SERIAL_4WAY_BLHELI_INTERFACE
466 #elif !defined(USE_SERIAL_4WAY_BLHELI_INTERFACE) && (defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) || defined(USE_SERIAL_4WAY_SK_BOOTLOADER))
467 #ifndef USE_SERIAL_4WAY_BLHELI_INTERFACE
468 #define USE_SERIAL_4WAY_BLHELI_INTERFACE
469 #endif
470 #endif
472 #if defined(USE_RX_PWM) || defined(USE_DSHOT) || defined(USE_LED_STRIP) || defined(USE_TRANSPONDER) || defined(USE_BEEPER) || defined(USE_SERIAL_4WAY_BLHELI_INTERFACE)
473 #ifndef USE_PWM_OUTPUT
474 #define USE_PWM_OUTPUT
475 #endif
476 #endif
478 #if !defined(USE_LED_STRIP)
479 #undef USE_LED_STRIP_STATUS_MODE
480 #endif
482 #if defined(USE_MAX7456) || defined(USE_FRSKYOSD) || defined(USE_MSP_DISPLAYPORT)
483 #ifndef USE_VIDEO_SYSTEM
484 #define USE_VIDEO_SYSTEM
485 #endif
486 #endif
488 #if defined(USE_LED_STRIP) && !defined(USE_LED_STRIP_STATUS_MODE)
489 #define USE_WS2811_SINGLE_COLOUR
490 #endif
492 #if defined(SIMULATOR_BUILD) || defined(UNIT_TEST)
493 // This feature uses 'arm_math.h', which does not exist for x86.
494 #undef USE_DYN_NOTCH_FILTER
495 #endif
497 #ifndef USE_CMS
498 #undef USE_CMS_FAILSAFE_MENU
499 #endif
501 #ifndef USE_DSHOT
502 #undef USE_DSHOT_TELEMETRY
503 #undef USE_DSHOT_BITBANG
504 #endif
506 #ifndef USE_DSHOT_TELEMETRY
507 #undef USE_RPM_FILTER
508 #undef USE_DSHOT_TELEMETRY_STATS
509 #undef USE_DYN_IDLE
510 #endif
512 #if !defined(USE_BOARD_INFO)
513 #undef USE_SIGNATURE
514 #endif
516 #if !defined(USE_ACC)
517 #undef USE_GPS_RESCUE
518 #undef USE_ACRO_TRAINER
519 #endif
521 #if (!defined(USE_GPS_RESCUE) || !defined(USE_CMS_FAILSAFE_MENU))
522 #undef USE_CMS_GPS_RESCUE_MENU
523 #endif
525 #ifndef USE_BEEPER
526 #undef BEEPER_PIN
527 #undef BEEPER_PWM_HZ
528 #endif
530 #if defined(USE_DMA_SPEC)
531 #define USE_TIMER_DMA
532 #else
533 #undef USE_TIMER_MGMT
534 #endif
536 #if defined(USE_TIMER_MGMT)
537 #undef USED_TIMERS
538 #endif
540 #if !defined(USE_RANGEFINDER)
541 #undef USE_RANGEFINDER_HCSR04
542 #undef USE_RANGEFINDER_SRF10
543 #undef USE_RANGEFINDER_HCSR04_I2C
544 #undef USE_RANGEFINDER_VL53L0X
545 #undef USE_RANGEFINDER_UIB
546 #undef USE_RANGEFINDER_TF
547 #endif
549 #ifndef USE_GPS_RESCUE
550 #undef USE_CMS_GPS_RESCUE_MENU
551 #endif
554 #if defined(CONFIG_IN_RAM) || defined(CONFIG_IN_FILE) || defined(CONFIG_IN_EXTERNAL_FLASH) || defined(CONFIG_IN_SDCARD) || defined(CONFIG_IN_MEMORY_MAPPED_FLASH)
555 #ifndef EEPROM_SIZE
556 #define EEPROM_SIZE 4096
557 #endif
558 extern uint8_t eepromData[EEPROM_SIZE];
559 #define __config_start (*eepromData)
560 #define __config_end (*ARRAYEND(eepromData))
561 #else
562 #ifndef CONFIG_IN_FLASH
563 #define CONFIG_IN_FLASH
564 #endif
565 extern uint8_t __config_start; // configured via linker script when building binaries.
566 extern uint8_t __config_end;
567 #endif
569 #if defined(USE_EXST) && !defined(RAMBASED)
570 #define USE_FLASH_BOOT_LOADER
571 #endif
573 #if defined(USE_FLASH_MEMORY_MAPPED)
574 #if !defined(USE_RAM_CODE)
575 #define USE_RAM_CODE
576 #endif
578 #define MMFLASH_CODE RAM_CODE
579 #define MMFLASH_CODE_NOINLINE RAM_CODE NOINLINE
581 #define MMFLASH_DATA FAST_DATA
582 #define MMFLASH_DATA_ZERO_INIT FAST_DATA_ZERO_INIT
583 #else
584 #define MMFLASH_CODE
585 #define MMFLASH_CODE_NOINLINE
586 #define MMFLASH_DATA
587 #define MMFLASH_DATA_ZERO_INIT
588 #endif
590 #ifdef USE_RAM_CODE
591 // RAM_CODE for methods that need to be in RAM, but don't need to be in the fastest type of memory.
592 // 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
593 #define RAM_CODE __attribute__((section(".ram_code")))
594 #endif
596 #ifndef USE_ITERM_RELAX
597 #undef USE_ABSOLUTE_CONTROL
598 #endif
600 #if defined(USE_RX_EXPRESSLRS)
601 // ELRS depends on CRSF telemetry
602 #if !defined(USE_TELEMETRY)
603 #define USE_TELEMETRY
604 #endif
605 #if !defined(USE_TELEMETRY_CRSF)
606 #define USE_TELEMETRY_CRSF
607 #endif
608 #if !defined(USE_CRSF_LINK_STATISTICS)
609 #define USE_CRSF_LINK_STATISTICS
610 #endif
611 #if !defined(USE_SERIALRX_CRSF)
612 #define USE_SERIALRX_CRSF
613 #endif
614 #endif
616 #if defined(USE_RX_SPI) || defined(USE_SERIALRX_SRXL2) || defined(USE_SERIALRX_CRSF)
617 #define USE_RX_BIND
618 #endif
620 #ifndef USE_GPS
621 #undef USE_GPS_PLUS_CODES
622 #undef USE_GPS_LAP_TIMER
623 #endif
625 #ifdef USE_GPS_LAP_TIMER
626 #define USE_CMS_GPS_LAP_TIMER_MENU
627 #endif
629 // Enable PINIO by default if any PIN is defined
630 #if !defined(USE_PINIO) && (defined(PINIO1_BOX) || defined(PINIO2_BOX) || defined(PINIO3_BOX) || defined(PINIO4_BOX))
631 #define USE_PINIO
632 #endif
634 #ifdef USE_PINIO
635 #ifndef USE_PINIOBOX
636 #define USE_PINIOBOX
637 #endif
638 #ifndef USE_PIN_PULL_UP_DOWN
639 #define USE_PIN_PULL_UP_DOWN
640 #endif
641 #endif // USE_PINIO