Fix function brace style
[betaflight.git] / src / main / target / common_pre.h
blob23c09be2f1237a2f26817be4cc3fd4bdff9aa3d7
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 #ifdef STM32F4
32 #if defined(STM32F40_41xxx)
33 #define USE_FAST_DATA
34 #endif
35 #define USE_DSHOT
36 #define USE_DSHOT_BITBANG
37 #define USE_DSHOT_TELEMETRY
38 #define USE_DSHOT_TELEMETRY_STATS
39 #define USE_RPM_FILTER
40 #define USE_DYN_IDLE
41 #define USE_DYN_NOTCH_FILTER
42 #define USE_ADC_INTERNAL
43 #define USE_USB_CDC_HID
44 #define USE_USB_MSC
45 #define USE_PERSISTENT_MSC_RTC
46 #define USE_MCO
47 #define USE_DMA_SPEC
48 #define USE_TIMER_MGMT
49 #define USE_PERSISTENT_OBJECTS
50 #define USE_CUSTOM_DEFAULTS_ADDRESS
51 #define USE_LATE_TASK_STATISTICS
53 #if defined(STM32F40_41xxx) || defined(STM32F411xE)
54 #define USE_OVERCLOCK
55 #endif
56 #endif // STM32F4
58 #ifdef STM32F7
59 #define USE_ITCM_RAM
60 #define ITCM_RAM_OPTIMISATION "-O2", "-freorder-blocks-algorithm=simple"
61 #define USE_FAST_DATA
62 #define USE_DSHOT
63 #define USE_DSHOT_BITBANG
64 #define USE_DSHOT_TELEMETRY
65 #define USE_DSHOT_TELEMETRY_STATS
66 #define USE_RPM_FILTER
67 #define USE_DYN_IDLE
68 #define USE_DYN_NOTCH_FILTER
69 #define USE_OVERCLOCK
70 #define USE_ADC_INTERNAL
71 #define USE_USB_CDC_HID
72 #define USE_USB_MSC
73 #define USE_PERSISTENT_MSC_RTC
74 #define USE_MCO
75 #define USE_DMA_SPEC
76 #define USE_TIMER_MGMT
77 #define USE_PERSISTENT_OBJECTS
78 #define USE_CUSTOM_DEFAULTS_ADDRESS
79 #define USE_LATE_TASK_STATISTICS
80 #endif // STM32F7
82 #ifdef STM32H7
83 #define USE_ITCM_RAM
84 #define USE_FAST_DATA
85 #define USE_DSHOT
86 #define USE_DSHOT_BITBANG
87 #define USE_DSHOT_TELEMETRY
88 #define USE_DSHOT_TELEMETRY_STATS
89 #define USE_RPM_FILTER
90 #define USE_DYN_IDLE
91 #define USE_DYN_NOTCH_FILTER
92 #define USE_ADC_INTERNAL
93 #define USE_USB_CDC_HID
94 #define USE_DMA_SPEC
95 #define USE_TIMER_MGMT
96 #define USE_PERSISTENT_OBJECTS
97 #define USE_DMA_RAM
98 #define USE_USB_MSC
99 #define USE_RTC_TIME
100 #define USE_PERSISTENT_MSC_RTC
101 #define USE_DSHOT_CACHE_MGMT
102 #define USE_LATE_TASK_STATISTICS
103 #endif
105 #ifdef STM32G4
106 #define USE_FAST_RAM
107 #define USE_DSHOT
108 #define USE_DSHOT_BITBANG
109 #define USE_DSHOT_TELEMETRY
110 #define USE_DSHOT_TELEMETRY_STATS
111 #define USE_RPM_FILTER
112 #define USE_DYN_IDLE
113 #define USE_OVERCLOCK
114 #define USE_DYN_NOTCH_FILTER
115 #define USE_ADC_INTERNAL
116 #define USE_USB_MSC
117 #define USE_USB_CDC_HID
118 #define USE_MCO
119 #define USE_DMA_SPEC
120 #define USE_TIMER_MGMT
121 #define USE_LATE_TASK_STATISTICS
122 #endif
124 #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
125 #define TASK_GYROPID_DESIRED_PERIOD 125 // 125us = 8kHz
126 #define SCHEDULER_DELAY_LIMIT 10
127 #else
128 #define TASK_GYROPID_DESIRED_PERIOD 1000 // 1000us = 1kHz
129 #define SCHEDULER_DELAY_LIMIT 100
130 #endif
132 #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
133 #define DEFAULT_AUX_CHANNEL_COUNT MAX_AUX_CHANNEL_COUNT
134 #else
135 #define DEFAULT_AUX_CHANNEL_COUNT 6
136 #endif
138 // Set the default cpu_overclock to the first level (108MHz) for F411
139 // Helps with looptime stability as the CPU is borderline when running native gyro sampling
140 #if defined(USE_OVERCLOCK) && defined(STM32F411xE)
141 #define DEFAULT_CPU_OVERCLOCK 1
142 #else
143 #define DEFAULT_CPU_OVERCLOCK 0
144 #endif
146 #if defined(STM32H7)
147 // Move ISRs to fast ram to avoid flash latency.
148 #define FAST_IRQ_HANDLER FAST_CODE
149 #else
150 #define FAST_IRQ_HANDLER
151 #endif
154 #ifdef USE_ITCM_RAM
155 #if defined(ITCM_RAM_OPTIMISATION) && !defined(DEBUG)
156 #define FAST_CODE __attribute__((section(".tcm_code"))) __attribute__((optimize(ITCM_RAM_OPTIMISATION)))
157 #else
158 #define FAST_CODE __attribute__((section(".tcm_code")))
159 #endif
160 // Handle case where we'd prefer code to be in ITCM, but it won't fit on the F745
161 #ifdef STM32F745xx
162 #define FAST_CODE_PREF
163 #else
164 #define FAST_CODE_PREF __attribute__((section(".tcm_code")))
165 #endif
166 #define FAST_CODE_NOINLINE NOINLINE
167 #else
168 #define FAST_CODE
169 #define FAST_CODE_PREF
170 #define FAST_CODE_NOINLINE
171 #endif // USE_ITCM_RAM
173 #ifdef USE_CCM_CODE
174 #define CCM_CODE __attribute__((section(".ccm_code")))
175 #else
176 #define CCM_CODE
177 #endif
179 #ifdef USE_FAST_DATA
180 #define FAST_DATA_ZERO_INIT __attribute__ ((section(".fastram_bss"), aligned(4)))
181 #define FAST_DATA __attribute__ ((section(".fastram_data"), aligned(4)))
182 #else
183 #define FAST_DATA_ZERO_INIT
184 #define FAST_DATA
185 #endif // USE_FAST_DATA
187 #if defined(STM32F4) || defined(STM32G4)
188 // F4 can't DMA to/from CCM (core coupled memory) SRAM (where the stack lives)
189 // On G4 there is no specific DMA target memory
190 #define DMA_DATA_ZERO_INIT
191 #define DMA_DATA
192 #define STATIC_DMA_DATA_AUTO static
193 #elif defined (STM32F7)
194 // F7 has no cache coherency issues DMAing to/from DTCM, otherwise buffers must be cache aligned
195 #define DMA_DATA_ZERO_INIT FAST_DATA_ZERO_INIT
196 #define DMA_DATA FAST_DATA
197 #define STATIC_DMA_DATA_AUTO static DMA_DATA
198 #else
199 // DMA to/from any memory
200 #define DMA_DATA_ZERO_INIT __attribute__ ((section(".dmaram_bss"), aligned(32)))
201 #define DMA_DATA __attribute__ ((section(".dmaram_data"), aligned(32)))
202 #define STATIC_DMA_DATA_AUTO static DMA_DATA
203 #endif
205 #if defined(STM32F4) || defined (STM32H7)
206 // Data in RAM which is guaranteed to not be reset on hot reboot
207 #define PERSISTENT __attribute__ ((section(".persistent_data"), aligned(4)))
208 #endif
210 #ifdef USE_DMA_RAM
211 #if defined(STM32H7)
212 #define DMA_RAM __attribute__((section(".DMA_RAM"), aligned(32)))
213 #define DMA_RW_AXI __attribute__((section(".DMA_RW_AXI"), aligned(32)))
214 extern uint8_t _dmaram_start__;
215 extern uint8_t _dmaram_end__;
216 #elif defined(STM32G4)
217 #define DMA_RAM_R __attribute__((section(".DMA_RAM_R")))
218 #define DMA_RAM_W __attribute__((section(".DMA_RAM_W")))
219 #define DMA_RAM_RW __attribute__((section(".DMA_RAM_RW")))
220 #endif
221 #else
222 #define DMA_RAM
223 #define DMA_RW_AXI
224 #define DMA_RAM_R
225 #define DMA_RAM_W
226 #define DMA_RAM_RW
227 #endif
229 #define USE_BRUSHED_ESC_AUTODETECT // Detect if brushed motors are connected and set defaults appropriately to avoid motors spinning on boot
231 #define USE_MOTOR
232 #define USE_PWM_OUTPUT
233 #define USE_DMA
234 #define USE_TIMER
236 #define USE_CLI
237 #define USE_SERIAL_PASSTHROUGH
238 #define USE_GYRO_REGISTER_DUMP // Adds gyroregisters command to cli to dump configured register values
239 #define USE_IMU_CALC
241 #if (!defined(CLOUD_BUILD))
242 #define USE_PPM
243 #define USE_SERIAL_RX
244 #define USE_SERIALRX_CRSF // Team Black Sheep Crossfire protocol
245 #define USE_SERIALRX_GHST // ImmersionRC Ghost Protocol
246 #define USE_SERIALRX_IBUS // FlySky and Turnigy receivers
247 #define USE_SERIALRX_SBUS // Frsky and Futaba receivers
248 #define USE_SERIALRX_SPEKTRUM // SRXL, DSM2 and DSMX protocol
249 #define USE_SERIALRX_SUMD // Graupner Hott protocol
250 #endif
252 #if (TARGET_FLASH_SIZE > 256)
253 #define PID_PROFILE_COUNT 4
254 #define CONTROL_RATE_PROFILE_COUNT 4
255 #elif (TARGET_FLASH_SIZE > 128)
256 #define PID_PROFILE_COUNT 3
257 #define CONTROL_RATE_PROFILE_COUNT 4
258 #else
259 #define PID_PROFILE_COUNT 2
260 #define CONTROL_RATE_PROFILE_COUNT 3
261 #endif
263 #if (TARGET_FLASH_SIZE > 64)
264 #define USE_ACRO_TRAINER
265 #define USE_BLACKBOX
266 #define USE_CLI_BATCH
267 #define USE_RESOURCE_MGMT
268 #define USE_RUNAWAY_TAKEOFF // Runaway Takeoff Prevention (anti-taz)
269 #define USE_SERVOS
270 #if (!defined(CLOUD_BUILD))
271 #define USE_TELEMETRY
272 #define USE_TELEMETRY_FRSKY_HUB
273 #define USE_TELEMETRY_SMARTPORT
274 #endif
275 #endif
277 #if (TARGET_FLASH_SIZE > 128)
278 #define USE_GYRO_OVERFLOW_CHECK
279 #define USE_YAW_SPIN_RECOVERY
280 #define USE_DSHOT_DMAR
282 #if (!defined(CLOUD_BUILD))
283 #define USE_SERIALRX_FPORT // FrSky FPort
284 #define USE_TELEMETRY_CRSF
285 #define USE_TELEMETRY_GHST
286 #define USE_TELEMETRY_SRXL
287 #endif
289 #if ((TARGET_FLASH_SIZE > 256 && !defined(FEATURE_CUT_LEVEL)) || (FEATURE_CUT_LEVEL < 12))
290 #define USE_CMS
291 #define USE_MSP_DISPLAYPORT
292 #define USE_MSP_OVER_TELEMETRY
293 #define USE_OSD_OVER_MSP_DISPLAYPORT
294 #define USE_LED_STRIP
295 #endif
297 #if ((TARGET_FLASH_SIZE > 256 && !defined(FEATURE_CUT_LEVEL)) || (FEATURE_CUT_LEVEL < 11))
298 #define USE_VTX_COMMON
299 #define USE_VTX_CONTROL
300 #define USE_VTX_SMARTAUDIO
301 #define USE_VTX_TRAMP
302 #define USE_VTX_MSP
303 #endif
305 #if ((TARGET_FLASH_SIZE > 256 && !defined(FEATURE_CUT_LEVEL)) || (FEATURE_CUT_LEVEL < 10))
306 #define USE_VIRTUAL_CURRENT_METER
307 #define USE_CAMERA_CONTROL
308 #define USE_ESC_SENSOR
309 #define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
310 #define USE_RCDEVICE
311 #endif
313 #if ((TARGET_FLASH_SIZE > 256 && !defined(FEATURE_CUT_LEVEL)) || (FEATURE_CUT_LEVEL < 9))
314 #define USE_GYRO_LPF2
315 #endif
317 #if ((TARGET_FLASH_SIZE > 256 && !defined(FEATURE_CUT_LEVEL)) || (FEATURE_CUT_LEVEL < 8))
318 #define USE_LAUNCH_CONTROL
319 #define USE_DYN_LPF
320 #define USE_D_MIN
321 #endif
323 #if ((TARGET_FLASH_SIZE > 256 && !defined(FEATURE_CUT_LEVEL)) || (FEATURE_CUT_LEVEL < 7))
324 #define USE_THROTTLE_BOOST
325 #define USE_INTEGRATED_YAW_CONTROL
326 #endif
328 #if ((TARGET_FLASH_SIZE > 256 && !defined(FEATURE_CUT_LEVEL)) || (FEATURE_CUT_LEVEL < 6))
329 #define USE_ITERM_RELAX
330 #define USE_RC_SMOOTHING_FILTER
331 #define USE_THRUST_LINEARIZATION
332 #define USE_TPA_MODE
333 #endif
335 #if ((TARGET_FLASH_SIZE > 256 && !defined(FEATURE_CUT_LEVEL)) || (FEATURE_CUT_LEVEL < 5))
336 #define USE_PWM
337 #endif
339 #if ((TARGET_FLASH_SIZE > 256 && !defined(FEATURE_CUT_LEVEL)) || (FEATURE_CUT_LEVEL < 4))
340 #define USE_HUFFMAN
341 #define USE_PINIO
342 #define USE_PINIOBOX
343 #endif
345 #if ((TARGET_FLASH_SIZE > 256 && !defined(FEATURE_CUT_LEVEL)) || (FEATURE_CUT_LEVEL < 3))
346 #ifdef USE_SERIALRX_SPEKTRUM
347 #define USE_SPEKTRUM_BIND
348 #define USE_SPEKTRUM_BIND_PLUG
349 #define USE_SPEKTRUM_REAL_RSSI
350 #define USE_SPEKTRUM_FAKE_RSSI
351 #define USE_SPEKTRUM_RSSI_PERCENT_CONVERSION
352 #define USE_SPEKTRUM_VTX_CONTROL
353 #define USE_SPEKTRUM_VTX_TELEMETRY
354 #define USE_SPEKTRUM_CMS_TELEMETRY
355 #define USE_PIN_PULL_UP_DOWN
356 #endif
357 #endif
359 #if ((TARGET_FLASH_SIZE > 256 && !defined(FEATURE_CUT_LEVEL)) || (FEATURE_CUT_LEVEL < 2))
360 #if (!defined(CLOUD_BUILD))
361 #define USE_TELEMETRY_HOTT
362 #define USE_TELEMETRY_LTM
363 #define USE_SERIALRX_SUMH // Graupner legacy protocol
364 #define USE_SERIALRX_XBUS // JR
365 #endif
366 #endif
368 #if ((TARGET_FLASH_SIZE > 256 && !defined(FEATURE_CUT_LEVEL)) || (FEATURE_CUT_LEVEL < 1))
369 #define USE_BOARD_INFO
370 #define USE_EXTENDED_CMS_MENUS
371 #define USE_RTC_TIME
372 #define USE_RX_MSP
373 #define USE_ESC_SENSOR_INFO
374 #define USE_CRSF_CMS_TELEMETRY
375 #define USE_CRSF_LINK_STATISTICS
376 #define USE_RX_RSSI_DBM
377 #endif
379 #endif // TARGET_FLASH_SIZE > 128
381 #if (TARGET_FLASH_SIZE > 256)
382 #define USE_AIRMODE_LPF
383 #define USE_CANVAS
384 #define USE_FRSKYOSD
385 #define USE_GPS
386 #define USE_GPS_NMEA
387 #define USE_GPS_UBLOX
388 #define USE_GPS_RESCUE
389 #define USE_GYRO_DLPF_EXPERIMENTAL
390 #define USE_OSD
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_UNCOMMON_MIXERS
396 #define USE_SIGNATURE
397 #define USE_ABSOLUTE_CONTROL
398 #define USE_HOTT_TEXTMODE
399 #define USE_LED_STRIP_STATUS_MODE
400 #define USE_VARIO
401 #define USE_RX_LINK_QUALITY_INFO
402 #define USE_ESC_SENSOR_TELEMETRY
403 #define USE_OSD_PROFILES
404 #define USE_OSD_STICK_OVERLAY
405 #define USE_CMS_FAILSAFE_MENU
406 #define USE_CMS_GPS_RESCUE_MENU
407 #define USE_TELEMETRY_SENSORS_DISABLED_DETAILS
408 #define USE_VTX_TABLE
409 #define USE_PERSISTENT_STATS
410 #define USE_PROFILE_NAMES
411 #define USE_FEEDFORWARD
412 #define USE_CUSTOM_BOX_NAMES
413 #define USE_BATTERY_VOLTAGE_SAG_COMPENSATION
414 #define USE_RX_MSP_OVERRIDE
415 #define USE_SIMPLIFIED_TUNING
416 #define USE_RX_LINK_UPLINK_POWER
417 #define USE_CRSF_V3
418 #define USE_CRAFTNAME_MSGS
420 #if (!defined(CLOUD_BUILD))
421 #define USE_SERIALRX_JETIEXBUS
422 #define USE_TELEMETRY_IBUS
423 #define USE_TELEMETRY_IBUS_EXTENDED
424 #define USE_TELEMETRY_JETIEXBUS
425 #define USE_TELEMETRY_MAVLINK
426 #define USE_SERIALRX_SRXL2 // Spektrum SRXL2 protocol
427 #endif
428 #endif
430 #if (TARGET_FLASH_SIZE > 512)
431 #define USE_ESCSERIAL_SIMONK
432 #define USE_SERIAL_4WAY_SK_BOOTLOADER
433 #define USE_DASHBOARD
434 #define USE_EMFAT_AUTORUN
435 #define USE_EMFAT_ICON
436 #define USE_GPS_PLUS_CODES
437 #define USE_BATTERY_CONTINUE
438 #endif