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 #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"
33 // Using RX DMA disables the use of receive callbacks
34 #define USE_UART1_RX_DMA
35 #define USE_UART1_TX_DMA
41 #define USE_DYN_NOTCH_FILTER
46 #if defined(STM32F40_41xxx)
50 #define USE_DSHOT_BITBANG
51 #define USE_DSHOT_TELEMETRY
52 #define USE_DSHOT_TELEMETRY_STATS
53 #define USE_RPM_FILTER
55 #define USE_DYN_NOTCH_FILTER
56 #define USE_ADC_INTERNAL
57 #define USE_USB_CDC_HID
59 #define USE_PERSISTENT_MSC_RTC
62 #define USE_TIMER_MGMT
63 #define USE_PERSISTENT_OBJECTS
64 #define USE_CUSTOM_DEFAULTS_ADDRESS
65 #define USE_LATE_TASK_STATISTICS
67 #if defined(STM32F40_41xxx) || defined(STM32F411xE)
74 #define ITCM_RAM_OPTIMISATION "-O2"
77 #define USE_DSHOT_BITBANG
78 #define USE_DSHOT_TELEMETRY
79 #define USE_DSHOT_TELEMETRY_STATS
80 #define USE_RPM_FILTER
82 #define USE_DYN_NOTCH_FILTER
84 #define USE_ADC_INTERNAL
85 #define USE_USB_CDC_HID
87 #define USE_PERSISTENT_MSC_RTC
90 #define USE_TIMER_MGMT
91 #define USE_PERSISTENT_OBJECTS
92 #define USE_CUSTOM_DEFAULTS_ADDRESS
93 #define USE_LATE_TASK_STATISTICS
100 #define USE_DSHOT_BITBANG
101 #define USE_DSHOT_TELEMETRY
102 #define USE_DSHOT_TELEMETRY_STATS
103 #define USE_RPM_FILTER
105 #define USE_DYN_NOTCH_FILTER
106 #define USE_ADC_INTERNAL
107 #define USE_USB_CDC_HID
109 #define USE_TIMER_MGMT
110 #define USE_PERSISTENT_OBJECTS
114 #define USE_PERSISTENT_MSC_RTC
115 #define USE_DSHOT_CACHE_MGMT
116 #define USE_LATE_TASK_STATISTICS
122 #define USE_DSHOT_BITBANG
123 #define USE_DSHOT_TELEMETRY
124 #define USE_DSHOT_TELEMETRY_STATS
125 #define USE_RPM_FILTER
127 #define USE_OVERCLOCK
128 #define USE_DYN_NOTCH_FILTER
129 #define USE_ADC_INTERNAL
131 #define USE_USB_CDC_HID
134 #define USE_TIMER_MGMT
135 #define USE_LATE_TASK_STATISTICS
138 #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
139 #define TASK_GYROPID_DESIRED_PERIOD 125 // 125us = 8kHz
140 #define SCHEDULER_DELAY_LIMIT 10
142 #define TASK_GYROPID_DESIRED_PERIOD 1000 // 1000us = 1kHz
143 #define SCHEDULER_DELAY_LIMIT 100
146 #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
147 #define DEFAULT_AUX_CHANNEL_COUNT MAX_AUX_CHANNEL_COUNT
149 #define DEFAULT_AUX_CHANNEL_COUNT 6
152 // Set the default cpu_overclock to the first level (108MHz) for F411
153 // Helps with looptime stability as the CPU is borderline when running native gyro sampling
154 #if defined(USE_OVERCLOCK) && defined(STM32F411xE)
155 #define DEFAULT_CPU_OVERCLOCK 1
157 #define DEFAULT_CPU_OVERCLOCK 0
161 // Move ISRs to fast ram to avoid flash latency.
162 #define FAST_IRQ_HANDLER FAST_CODE
164 #define FAST_IRQ_HANDLER
169 #if defined(ITCM_RAM_OPTIMISATION) && !defined(DEBUG)
170 #define FAST_CODE __attribute__((section(".tcm_code"))) __attribute__((optimize(ITCM_RAM_OPTIMISATION)))
172 #define FAST_CODE __attribute__((section(".tcm_code")))
174 // Handle case where we'd prefer code to be in ITCM, but it won't fit on the F745
176 #define FAST_CODE_PREF
178 #define FAST_CODE_PREF __attribute__((section(".tcm_code")))
180 #define FAST_CODE_NOINLINE NOINLINE
183 #define FAST_CODE_PREF
184 #define FAST_CODE_NOINLINE
185 #endif // USE_ITCM_RAM
188 #define CCM_CODE __attribute__((section(".ccm_code")))
194 #define FAST_DATA_ZERO_INIT __attribute__ ((section(".fastram_bss"), aligned(4)))
195 #define FAST_DATA __attribute__ ((section(".fastram_data"), aligned(4)))
197 #define FAST_DATA_ZERO_INIT
199 #endif // USE_FAST_DATA
201 #if defined(STM32F4) || defined(STM32G4)
202 // F4 can't DMA to/from CCM (core coupled memory) SRAM (where the stack lives)
203 // On G4 there is no specific DMA target memory
204 #define DMA_DATA_ZERO_INIT
206 #define STATIC_DMA_DATA_AUTO static
207 #elif defined (STM32F7)
208 // F7 has no cache coherency issues DMAing to/from DTCM, otherwise buffers must be cache aligned
209 #define DMA_DATA_ZERO_INIT FAST_DATA_ZERO_INIT
210 #define DMA_DATA FAST_DATA
211 #define STATIC_DMA_DATA_AUTO static DMA_DATA
213 // DMA to/from any memory
214 #define DMA_DATA_ZERO_INIT __attribute__ ((section(".dmaram_bss"), aligned(32)))
215 #define DMA_DATA __attribute__ ((section(".dmaram_data"), aligned(32)))
216 #define STATIC_DMA_DATA_AUTO static DMA_DATA
219 #if defined(STM32F4) || defined (STM32H7)
220 // Data in RAM which is guaranteed to not be reset on hot reboot
221 #define PERSISTENT __attribute__ ((section(".persistent_data"), aligned(4)))
226 #define DMA_RAM __attribute__((section(".DMA_RAM"), aligned(32)))
227 #define DMA_RW_AXI __attribute__((section(".DMA_RW_AXI"), aligned(32)))
228 extern uint8_t _dmaram_start__
;
229 extern uint8_t _dmaram_end__
;
230 #elif defined(STM32G4)
231 #define DMA_RAM_R __attribute__((section(".DMA_RAM_R")))
232 #define DMA_RAM_W __attribute__((section(".DMA_RAM_W")))
233 #define DMA_RAM_RW __attribute__((section(".DMA_RAM_RW")))
243 #define USE_BRUSHED_ESC_AUTODETECT // Detect if brushed motors are connected and set defaults appropriately to avoid motors spinning on boot
246 #define USE_PWM_OUTPUT
251 #define USE_SERIAL_PASSTHROUGH
252 #define USE_GYRO_REGISTER_DUMP // Adds gyroregisters command to cli to dump configured register values
255 #define USE_SERIAL_RX
256 #define USE_SERIALRX_CRSF // Team Black Sheep Crossfire protocol
257 #define USE_SERIALRX_GHST // ImmersionRC Ghost Protocol
258 #define USE_SERIALRX_IBUS // FlySky and Turnigy receivers
259 #define USE_SERIALRX_SBUS // Frsky and Futaba receivers
260 #define USE_SERIALRX_SPEKTRUM // SRXL, DSM2 and DSMX protocol
261 #define USE_SERIALRX_SUMD // Graupner Hott protocol
263 #if (TARGET_FLASH_SIZE > 128)
264 #define PID_PROFILE_COUNT 3
265 #define CONTROL_RATE_PROFILE_COUNT 6
267 #define PID_PROFILE_COUNT 2
268 #define CONTROL_RATE_PROFILE_COUNT 3
271 #if (TARGET_FLASH_SIZE > 64)
272 #define USE_ACRO_TRAINER
274 #define USE_CLI_BATCH
275 #define USE_RESOURCE_MGMT
276 #define USE_RUNAWAY_TAKEOFF // Runaway Takeoff Prevention (anti-taz)
278 #define USE_TELEMETRY
279 #define USE_TELEMETRY_FRSKY_HUB
280 #define USE_TELEMETRY_SMARTPORT
283 #if (TARGET_FLASH_SIZE > 128)
284 #define USE_GYRO_OVERFLOW_CHECK
285 #define USE_YAW_SPIN_RECOVERY
286 #define USE_DSHOT_DMAR
287 #define USE_SERIALRX_FPORT // FrSky FPort
288 #define USE_TELEMETRY_CRSF
289 #define USE_TELEMETRY_GHST
290 #define USE_TELEMETRY_SRXL
292 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 12))
294 #define USE_MSP_DISPLAYPORT
295 #define USE_MSP_OVER_TELEMETRY
296 #define USE_OSD_OVER_MSP_DISPLAYPORT
297 #define USE_LED_STRIP
300 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 11))
301 #define USE_VTX_COMMON
302 #define USE_VTX_CONTROL
303 #define USE_VTX_SMARTAUDIO
304 #define USE_VTX_TRAMP
307 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 10))
308 #define USE_VIRTUAL_CURRENT_METER
309 #define USE_CAMERA_CONTROL
310 #define USE_ESC_SENSOR
311 #define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
315 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 9))
316 #define USE_GYRO_LPF2
319 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 8))
320 #define USE_LAUNCH_CONTROL
325 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 7))
326 #define USE_THROTTLE_BOOST
327 #define USE_INTEGRATED_YAW_CONTROL
330 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 6))
331 #define USE_ITERM_RELAX
332 #define USE_RC_SMOOTHING_FILTER
333 #define USE_THRUST_LINEARIZATION
337 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 5))
341 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 4))
347 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 3))
348 #ifdef USE_SERIALRX_SPEKTRUM
349 #define USE_SPEKTRUM_BIND
350 #define USE_SPEKTRUM_BIND_PLUG
351 #define USE_SPEKTRUM_REAL_RSSI
352 #define USE_SPEKTRUM_FAKE_RSSI
353 #define USE_SPEKTRUM_RSSI_PERCENT_CONVERSION
354 #define USE_SPEKTRUM_VTX_CONTROL
355 #define USE_SPEKTRUM_VTX_TELEMETRY
356 #define USE_SPEKTRUM_CMS_TELEMETRY
357 #define USE_PIN_PULL_UP_DOWN
361 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 2))
362 #define USE_TELEMETRY_HOTT
363 #define USE_TELEMETRY_LTM
364 #define USE_SERIALRX_SUMH // Graupner legacy protocol
365 #define USE_SERIALRX_XBUS // JR
368 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 1))
369 #define USE_BOARD_INFO
370 #define USE_EXTENDED_CMS_MENUS
373 #define USE_ESC_SENSOR_INFO
374 #define USE_CRSF_CMS_TELEMETRY
375 #define USE_CRSF_LINK_STATISTICS
376 #define USE_RX_RSSI_DBM
379 #endif // TARGET_FLASH_SIZE > 128
381 #if (TARGET_FLASH_SIZE > 256)
382 #define USE_AIRMODE_LPF
387 #define USE_GPS_UBLOX
388 #define USE_GPS_RESCUE
389 #define USE_GYRO_DLPF_EXPERIMENTAL
391 #define USE_OSD_OVER_MSP_DISPLAYPORT
392 #define USE_MULTI_GYRO
393 #define USE_OSD_ADJUSTMENTS
394 #define USE_SENSOR_NAMES
395 #define USE_SERIALRX_JETIEXBUS
396 #define USE_TELEMETRY_IBUS
397 #define USE_TELEMETRY_IBUS_EXTENDED
398 #define USE_TELEMETRY_JETIEXBUS
399 #define USE_TELEMETRY_MAVLINK
400 #define USE_UNCOMMON_MIXERS
401 #define USE_SIGNATURE
402 #define USE_ABSOLUTE_CONTROL
403 #define USE_HOTT_TEXTMODE
404 #define USE_LED_STRIP_STATUS_MODE
406 #define USE_RX_LINK_QUALITY_INFO
407 #define USE_ESC_SENSOR_TELEMETRY
408 #define USE_OSD_PROFILES
409 #define USE_OSD_STICK_OVERLAY
410 #define USE_CMS_FAILSAFE_MENU
411 #define USE_CMS_GPS_RESCUE_MENU
412 #define USE_TELEMETRY_SENSORS_DISABLED_DETAILS
413 #define USE_VTX_TABLE
414 #define USE_PERSISTENT_STATS
415 #define USE_PROFILE_NAMES
416 #define USE_SERIALRX_SRXL2 // Spektrum SRXL2 protocol
417 #define USE_FEEDFORWARD
418 #define USE_CUSTOM_BOX_NAMES
419 #define USE_BATTERY_VOLTAGE_SAG_COMPENSATION
420 #define USE_RX_MSP_OVERRIDE
421 #define USE_SIMPLIFIED_TUNING
422 #define USE_RX_LINK_UPLINK_POWER
426 #if (TARGET_FLASH_SIZE > 512)
427 #define USE_ESCSERIAL_SIMONK
428 #define USE_SERIAL_4WAY_SK_BOOTLOADER
429 #define USE_DASHBOARD
430 #define USE_EMFAT_AUTORUN
431 #define USE_EMFAT_ICON
432 #define USE_GPS_PLUS_CODES