New memory section types for DMA
[betaflight.git] / src / main / target / common_pre.h
blob998d59fc9894558d44c6dd0b9c71e74f91bad92b
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 //#define SCHEDULER_DEBUG // define this to use scheduler debug[] values. Undefined by default for performance reasons
33 #define I2C1_OVERCLOCK true
34 #define I2C2_OVERCLOCK true
36 #ifdef STM32F1
37 #define MINIMAL_CLI
38 // Using RX DMA disables the use of receive callbacks
39 #define USE_UART1_RX_DMA
40 #define USE_UART1_TX_DMA
41 #endif
43 #ifdef STM32F3
44 #define MINIMAL_CLI
45 #define USE_DSHOT
46 #define USE_GYRO_DATA_ANALYSE
47 #define USE_CCM_CODE
48 #endif
50 #ifdef STM32F4
51 #if defined(STM32F40_41xxx)
52 #define USE_FAST_DATA
53 #endif
54 #define USE_DSHOT
55 #define USE_DSHOT_BITBANG
56 #define USE_DSHOT_TELEMETRY
57 #define USE_DSHOT_TELEMETRY_STATS
58 #define USE_RPM_FILTER
59 #define USE_DYN_IDLE
60 #define I2C3_OVERCLOCK true
61 #define USE_GYRO_DATA_ANALYSE
62 #define USE_ADC
63 #define USE_ADC_INTERNAL
64 #define USE_USB_CDC_HID
65 #define USE_USB_MSC
66 #define USE_PERSISTENT_MSC_RTC
67 #define USE_MCO
68 #define USE_DMA_SPEC
69 #define USE_TIMER_MGMT
70 #define USE_PERSISTENT_OBJECTS
71 #define USE_CUSTOM_DEFAULTS_ADDRESS
72 #define USE_SPI_TRANSACTION
74 #if defined(STM32F40_41xxx) || defined(STM32F411xE)
75 #define USE_OVERCLOCK
76 #endif
78 #endif // STM32F4
80 #ifdef STM32F7
81 #define USE_ITCM_RAM
82 #define USE_FAST_DATA
83 #define USE_DSHOT
84 #define USE_DSHOT_BITBANG
85 #define USE_DSHOT_TELEMETRY
86 #define USE_DSHOT_TELEMETRY_STATS
87 #define USE_RPM_FILTER
88 #define USE_DYN_IDLE
89 #define I2C3_OVERCLOCK true
90 #define I2C4_OVERCLOCK true
91 #define USE_GYRO_DATA_ANALYSE
92 #define USE_OVERCLOCK
93 #define USE_ADC_INTERNAL
94 #define USE_USB_CDC_HID
95 #define USE_USB_MSC
96 #define USE_PERSISTENT_MSC_RTC
97 #define USE_MCO
98 #define USE_DMA_SPEC
99 #define USE_TIMER_MGMT
100 #define USE_PERSISTENT_OBJECTS
101 #define USE_CUSTOM_DEFAULTS_ADDRESS
102 #define USE_SPI_TRANSACTION
103 #endif // STM32F7
105 #ifdef STM32H7
106 #define USE_ITCM_RAM
107 #define USE_FAST_DATA
108 #define USE_DSHOT
109 #define USE_DSHOT_BITBANG
110 #define USE_DSHOT_TELEMETRY
111 #define USE_DSHOT_TELEMETRY_STATS
112 #define USE_RPM_FILTER
113 #define USE_DYN_IDLE
114 #define I2C3_OVERCLOCK true
115 #define I2C4_OVERCLOCK true
116 #define USE_GYRO_DATA_ANALYSE
117 #define USE_ADC_INTERNAL
118 #define USE_USB_CDC_HID
119 #define USE_DMA_SPEC
120 #define USE_TIMER_MGMT
121 #define USE_PERSISTENT_OBJECTS
122 #define USE_DMA_RAM
123 #define USE_USB_MSC
124 #define USE_RTC_TIME
125 #define USE_PERSISTENT_MSC_RTC
126 #define USE_DSHOT_CACHE_MGMT
127 #define USE_LATE_TASK_STATISTICS
128 #endif
130 #ifdef STM32G4
131 #define USE_FAST_RAM
132 #define USE_DSHOT
133 #define USE_DSHOT_BITBANG
134 #define USE_DSHOT_TELEMETRY
135 #define USE_DSHOT_TELEMETRY_STATS
136 #define USE_RPM_FILTER
137 #define USE_DYN_IDLE
138 #define I2C3_OVERCLOCK true
139 #define I2C4_OVERCLOCK true
140 #define USE_OVERCLOCK
141 #define USE_GYRO_DATA_ANALYSE
142 #define USE_ADC_INTERNAL
143 #define USE_USB_MSC
144 #define USE_USB_CDC_HID
145 #define USE_MCO
146 #define USE_DMA_SPEC
147 #define USE_TIMER_MGMT
148 #endif
150 #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
151 #define TASK_GYROPID_DESIRED_PERIOD 125 // 125us = 8kHz
152 #define SCHEDULER_DELAY_LIMIT 10
153 #else
154 #define TASK_GYROPID_DESIRED_PERIOD 1000 // 1000us = 1kHz
155 #define SCHEDULER_DELAY_LIMIT 100
156 #endif
158 #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
159 #define DEFAULT_AUX_CHANNEL_COUNT MAX_AUX_CHANNEL_COUNT
160 #else
161 #define DEFAULT_AUX_CHANNEL_COUNT 6
162 #endif
164 // Set the default cpu_overclock to the first level (108MHz) for F411
165 // Helps with looptime stability as the CPU is borderline when running native gyro sampling
166 #if defined(USE_OVERCLOCK) && defined(STM32F411xE)
167 #define DEFAULT_CPU_OVERCLOCK 1
168 #else
169 #define DEFAULT_CPU_OVERCLOCK 0
170 #endif
173 #ifdef USE_ITCM_RAM
174 #define FAST_CODE __attribute__((section(".tcm_code")))
175 #define FAST_CODE_NOINLINE NOINLINE
176 #else
177 #define FAST_CODE
178 #define FAST_CODE_NOINLINE
179 #endif // USE_ITCM_RAM
181 #ifdef USE_CCM_CODE
182 #define CCM_CODE __attribute__((section(".ccm_code")))
183 #else
184 #define CCM_CODE
185 #endif
187 #ifdef USE_FAST_DATA
188 #define FAST_DATA_ZERO_INIT __attribute__ ((section(".fastram_bss"), aligned(4)))
189 #define FAST_DATA __attribute__ ((section(".fastram_data"), aligned(4)))
190 #else
191 #define FAST_DATA_ZERO_INIT
192 #define FAST_DATA
193 #endif // USE_FAST_DATA
195 #if defined(STM32F4)
196 // F4 can't DMA to/from CCM (core coupled memory) SRAM (where the stack lives)
197 #define DMA_DATA_ZERO_INIT
198 #define DMA_DATA
199 #define DMA_DATA_AUTO static
200 #elif defined (STM32F7)
201 // F7 has no cache coherency issues DMAing to/from DTCM, otherwise buffers must be cache aligned
202 #define DMA_DATA_ZERO_INIT FAST_DATA_ZERO_INIT
203 #define DMA_DATA FAST_DATA
204 #define DMA_DATA_AUTO static DMA_DATA
205 #else
206 // DMA to/from any memory
207 #define DMA_DATA_ZERO_INIT __attribute__ ((section(".dmaram_bss"), aligned(32)))
208 #define DMA_DATA __attribute__ ((section(".dmaram_data"), aligned(32)))
209 #define DMA_DATA_AUTO static DMA_DATA
210 #endif
212 #if defined(STM32F4) || defined (STM32H7)
213 // Data in RAM which is guaranteed to not be reset on hot reboot
214 #define PERSISTENT __attribute__ ((section(".persistent_data"), aligned(4)))
215 #endif
217 #ifdef USE_DMA_RAM
218 #if defined(STM32H7)
219 #define DMA_RAM __attribute__((section(".DMA_RAM"), aligned(32)))
220 #define DMA_RW_AXI __attribute__((section(".DMA_RW_AXI"), aligned(32)))
221 extern uint8_t _dmaram_start__;
222 extern uint8_t _dmaram_end__;
223 #elif defined(STM32G4)
224 #define DMA_RAM_R __attribute__((section(".DMA_RAM_R")))
225 #define DMA_RAM_W __attribute__((section(".DMA_RAM_W")))
226 #define DMA_RAM_RW __attribute__((section(".DMA_RAM_RW")))
227 #endif
228 #else
229 #define DMA_RAM
230 #define DMA_RW_AXI
231 #define DMA_RAM_R
232 #define DMA_RAM_W
233 #define DMA_RAM_RW
234 #endif
236 #define USE_BRUSHED_ESC_AUTODETECT // Detect if brushed motors are connected and set defaults appropriately to avoid motors spinning on boot
238 #define USE_MOTOR
239 #define USE_PWM_OUTPUT
240 #define USE_DMA
241 #define USE_TIMER
243 #define USE_CLI
244 #define USE_SERIAL_PASSTHROUGH
245 #define USE_TASK_STATISTICS
246 #define USE_GYRO_REGISTER_DUMP // Adds gyroregisters command to cli to dump configured register values
247 #define USE_IMU_CALC
248 #define USE_PPM
249 #define USE_SERIAL_RX
250 #define USE_SERIALRX_CRSF // Team Black Sheep Crossfire protocol
251 #define USE_SERIALRX_GHST // ImmersionRC Ghost Protocol
252 #define USE_SERIALRX_IBUS // FlySky and Turnigy receivers
253 #define USE_SERIALRX_SBUS // Frsky and Futaba receivers
254 #define USE_SERIALRX_SPEKTRUM // SRXL, DSM2 and DSMX protocol
255 #define USE_SERIALRX_SUMD // Graupner Hott protocol
257 #if (TARGET_FLASH_SIZE > 128)
258 #define PID_PROFILE_COUNT 3
259 #define CONTROL_RATE_PROFILE_COUNT 6
260 #else
261 #define PID_PROFILE_COUNT 2
262 #define CONTROL_RATE_PROFILE_COUNT 3
263 #endif
265 #if (TARGET_FLASH_SIZE > 64)
266 #define USE_ACRO_TRAINER
267 #define USE_BLACKBOX
268 #define USE_CLI_BATCH
269 #define USE_RESOURCE_MGMT
270 #define USE_RUNAWAY_TAKEOFF // Runaway Takeoff Prevention (anti-taz)
271 #define USE_SERVOS
272 #define USE_TELEMETRY
273 #define USE_TELEMETRY_FRSKY_HUB
274 #define USE_TELEMETRY_SMARTPORT
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
281 #define USE_SERIALRX_FPORT // FrSky FPort
282 #define USE_TELEMETRY_CRSF
283 #define USE_TELEMETRY_GHST
284 #define USE_TELEMETRY_SRXL
286 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 12))
287 #define USE_CMS
288 #define USE_MSP_DISPLAYPORT
289 #define USE_MSP_OVER_TELEMETRY
290 #define USE_OSD_OVER_MSP_DISPLAYPORT
291 #define USE_LED_STRIP
292 #endif
294 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 11))
295 #define USE_VTX_COMMON
296 #define USE_VTX_CONTROL
297 #define USE_VTX_SMARTAUDIO
298 #define USE_VTX_TRAMP
299 #endif
301 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 10))
302 #define USE_VIRTUAL_CURRENT_METER
303 #define USE_CAMERA_CONTROL
304 #define USE_ESC_SENSOR
305 #define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
306 #define USE_RCDEVICE
307 #endif
309 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 9))
310 #define USE_GYRO_LPF2
311 #endif
313 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 8))
314 #define USE_LAUNCH_CONTROL
315 #define USE_DYN_LPF
316 #define USE_D_MIN
317 #endif
319 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 7))
320 #define USE_THROTTLE_BOOST
321 #define USE_INTEGRATED_YAW_CONTROL
322 #endif
324 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 6))
325 #define USE_ITERM_RELAX
326 #define USE_RC_SMOOTHING_FILTER
327 #define USE_THRUST_LINEARIZATION
328 #define USE_TPA_MODE
329 #endif
331 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 5))
332 #define USE_PWM
333 #endif
335 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 4))
336 #define USE_HUFFMAN
337 #define USE_PINIO
338 #define USE_PINIOBOX
339 #endif
341 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 3))
342 #ifdef USE_SERIALRX_SPEKTRUM
343 #define USE_SPEKTRUM_BIND
344 #define USE_SPEKTRUM_BIND_PLUG
345 #define USE_SPEKTRUM_REAL_RSSI
346 #define USE_SPEKTRUM_FAKE_RSSI
347 #define USE_SPEKTRUM_RSSI_PERCENT_CONVERSION
348 #define USE_SPEKTRUM_VTX_CONTROL
349 #define USE_SPEKTRUM_VTX_TELEMETRY
350 #define USE_SPEKTRUM_CMS_TELEMETRY
351 #define USE_PIN_PULL_UP_DOWN
352 #endif
353 #endif
355 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 2))
356 #define USE_TELEMETRY_HOTT
357 #define USE_TELEMETRY_LTM
358 #define USE_SERIALRX_SUMH // Graupner legacy protocol
359 #define USE_SERIALRX_XBUS // JR
360 #endif
362 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 1))
363 #define USE_BOARD_INFO
364 #define USE_EXTENDED_CMS_MENUS
365 #define USE_RTC_TIME
366 #define USE_RX_MSP
367 #define USE_ESC_SENSOR_INFO
368 #define USE_CRSF_CMS_TELEMETRY
369 #define USE_CRSF_LINK_STATISTICS
370 #define USE_RX_RSSI_DBM
371 #endif
373 #endif // TARGET_FLASH_SIZE > 128
375 #if (TARGET_FLASH_SIZE > 256)
376 #define USE_AIRMODE_LPF
377 #define USE_CANVAS
378 #define USE_DASHBOARD
379 #define USE_FRSKYOSD
380 #define USE_GPS
381 #define USE_GPS_NMEA
382 #define USE_GPS_UBLOX
383 #define USE_GPS_RESCUE
384 #define USE_GYRO_DLPF_EXPERIMENTAL
385 #define USE_OSD
386 #define USE_OSD_OVER_MSP_DISPLAYPORT
387 #define USE_MULTI_GYRO
388 #define USE_OSD_ADJUSTMENTS
389 #define USE_SENSOR_NAMES
390 #define USE_SERIALRX_JETIEXBUS
391 #define USE_TELEMETRY_IBUS
392 #define USE_TELEMETRY_IBUS_EXTENDED
393 #define USE_TELEMETRY_JETIEXBUS
394 #define USE_TELEMETRY_MAVLINK
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_ESCSERIAL_SIMONK
406 #define USE_SERIAL_4WAY_SK_BOOTLOADER
407 #define USE_CMS_FAILSAFE_MENU
408 #define USE_CMS_GPS_RESCUE_MENU
409 #define USE_TELEMETRY_SENSORS_DISABLED_DETAILS
410 #define USE_VTX_TABLE
411 #define USE_PERSISTENT_STATS
412 #define USE_PROFILE_NAMES
413 #define USE_SERIALRX_SRXL2 // Spektrum SRXL2 protocol
414 #define USE_INTERPOLATED_SP
415 #define USE_CUSTOM_BOX_NAMES
416 #define USE_BATTERY_VOLTAGE_SAG_COMPENSATION
417 #define USE_RX_MSP_OVERRIDE
418 #define USE_SIMPLIFIED_TUNING
419 #define USE_RX_LINK_UPLINK_POWER
420 #define USE_GPS_PLUS_CODES
421 #endif