I2C configurable clockspeed
[betaflight.git] / src / main / target / common_pre.h
blob0f3c448b0b05484bf39e7be8a63a835db3ccb92b
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 #ifdef STM32F1
34 #define MINIMAL_CLI
35 // Using RX DMA disables the use of receive callbacks
36 #define USE_UART1_RX_DMA
37 #define USE_UART1_TX_DMA
38 #endif
40 #ifdef STM32F3
41 #define MINIMAL_CLI
42 #define USE_DSHOT
43 #define USE_GYRO_DATA_ANALYSE
44 #define USE_CCM_CODE
45 #endif
47 #ifdef STM32F4
48 #if defined(STM32F40_41xxx)
49 #define USE_FAST_DATA
50 #endif
51 #define USE_DSHOT
52 #define USE_DSHOT_BITBANG
53 #define USE_DSHOT_TELEMETRY
54 #define USE_DSHOT_TELEMETRY_STATS
55 #define USE_RPM_FILTER
56 #define USE_DYN_IDLE
57 #define USE_GYRO_DATA_ANALYSE
58 #define USE_ADC
59 #define USE_ADC_INTERNAL
60 #define USE_USB_CDC_HID
61 #define USE_USB_MSC
62 #define USE_PERSISTENT_MSC_RTC
63 #define USE_MCO
64 #define USE_DMA_SPEC
65 #define USE_TIMER_MGMT
66 #define USE_PERSISTENT_OBJECTS
67 #define USE_CUSTOM_DEFAULTS_ADDRESS
68 #define USE_SPI_TRANSACTION
70 #if defined(STM32F40_41xxx) || defined(STM32F411xE)
71 #define USE_OVERCLOCK
72 #endif
74 #endif // STM32F4
76 #ifdef STM32F7
77 #define USE_ITCM_RAM
78 #define USE_FAST_DATA
79 #define USE_DSHOT
80 #define USE_DSHOT_BITBANG
81 #define USE_DSHOT_TELEMETRY
82 #define USE_DSHOT_TELEMETRY_STATS
83 #define USE_RPM_FILTER
84 #define USE_DYN_IDLE
85 #define USE_GYRO_DATA_ANALYSE
86 #define USE_OVERCLOCK
87 #define USE_ADC_INTERNAL
88 #define USE_USB_CDC_HID
89 #define USE_USB_MSC
90 #define USE_PERSISTENT_MSC_RTC
91 #define USE_MCO
92 #define USE_DMA_SPEC
93 #define USE_TIMER_MGMT
94 #define USE_PERSISTENT_OBJECTS
95 #define USE_CUSTOM_DEFAULTS_ADDRESS
96 #define USE_SPI_TRANSACTION
97 #endif // STM32F7
99 #ifdef STM32H7
100 #define USE_ITCM_RAM
101 #define USE_FAST_DATA
102 #define USE_DSHOT
103 #define USE_DSHOT_BITBANG
104 #define USE_DSHOT_TELEMETRY
105 #define USE_DSHOT_TELEMETRY_STATS
106 #define USE_RPM_FILTER
107 #define USE_DYN_IDLE
108 #define USE_GYRO_DATA_ANALYSE
109 #define USE_ADC_INTERNAL
110 #define USE_USB_CDC_HID
111 #define USE_DMA_SPEC
112 #define USE_TIMER_MGMT
113 #define USE_PERSISTENT_OBJECTS
114 #define USE_DMA_RAM
115 #define USE_USB_MSC
116 #define USE_RTC_TIME
117 #define USE_PERSISTENT_MSC_RTC
118 #define USE_DSHOT_CACHE_MGMT
119 #define USE_LATE_TASK_STATISTICS
120 #endif
122 #ifdef STM32G4
123 #define USE_FAST_RAM
124 #define USE_DSHOT
125 #define USE_DSHOT_BITBANG
126 #define USE_DSHOT_TELEMETRY
127 #define USE_DSHOT_TELEMETRY_STATS
128 #define USE_RPM_FILTER
129 #define USE_DYN_IDLE
130 #define USE_OVERCLOCK
131 #define USE_GYRO_DATA_ANALYSE
132 #define USE_ADC_INTERNAL
133 #define USE_USB_MSC
134 #define USE_USB_CDC_HID
135 #define USE_MCO
136 #define USE_DMA_SPEC
137 #define USE_TIMER_MGMT
138 #endif
140 #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
141 #define TASK_GYROPID_DESIRED_PERIOD 125 // 125us = 8kHz
142 #define SCHEDULER_DELAY_LIMIT 10
143 #else
144 #define TASK_GYROPID_DESIRED_PERIOD 1000 // 1000us = 1kHz
145 #define SCHEDULER_DELAY_LIMIT 100
146 #endif
148 #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
149 #define DEFAULT_AUX_CHANNEL_COUNT MAX_AUX_CHANNEL_COUNT
150 #else
151 #define DEFAULT_AUX_CHANNEL_COUNT 6
152 #endif
154 // Set the default cpu_overclock to the first level (108MHz) for F411
155 // Helps with looptime stability as the CPU is borderline when running native gyro sampling
156 #if defined(USE_OVERCLOCK) && defined(STM32F411xE)
157 #define DEFAULT_CPU_OVERCLOCK 1
158 #else
159 #define DEFAULT_CPU_OVERCLOCK 0
160 #endif
163 #ifdef USE_ITCM_RAM
164 #define FAST_CODE __attribute__((section(".tcm_code")))
165 #define FAST_CODE_NOINLINE NOINLINE
166 #else
167 #define FAST_CODE
168 #define FAST_CODE_NOINLINE
169 #endif // USE_ITCM_RAM
171 #ifdef USE_CCM_CODE
172 #define CCM_CODE __attribute__((section(".ccm_code")))
173 #else
174 #define CCM_CODE
175 #endif
177 #ifdef USE_FAST_DATA
178 #define FAST_DATA_ZERO_INIT __attribute__ ((section(".fastram_bss"), aligned(4)))
179 #define FAST_DATA __attribute__ ((section(".fastram_data"), aligned(4)))
180 #else
181 #define FAST_DATA_ZERO_INIT
182 #define FAST_DATA
183 #endif // USE_FAST_DATA
185 #if defined(STM32F4) || defined (STM32H7)
186 // Data in RAM which is guaranteed to not be reset on hot reboot
187 #define PERSISTENT __attribute__ ((section(".persistent_data"), aligned(4)))
188 #endif
190 #ifdef USE_DMA_RAM
191 #if defined(STM32H7)
192 #define DMA_RAM __attribute__((section(".DMA_RAM")))
193 #define DMA_RW_AXI __attribute__((section(".DMA_RW_AXI")))
194 #elif defined(STM32G4)
195 #define DMA_RAM_R __attribute__((section(".DMA_RAM_R")))
196 #define DMA_RAM_W __attribute__((section(".DMA_RAM_W")))
197 #define DMA_RAM_RW __attribute__((section(".DMA_RAM_RW")))
198 #endif
199 #else
200 #define DMA_RAM
201 #define DMA_RW_AXI
202 #define DMA_RAM_R
203 #define DMA_RAM_W
204 #define DMA_RAM_RW
205 #endif
207 #define USE_BRUSHED_ESC_AUTODETECT // Detect if brushed motors are connected and set defaults appropriately to avoid motors spinning on boot
209 #define USE_MOTOR
210 #define USE_PWM_OUTPUT
211 #define USE_DMA
212 #define USE_TIMER
214 #define USE_CLI
215 #define USE_SERIAL_PASSTHROUGH
216 #define USE_TASK_STATISTICS
217 #define USE_GYRO_REGISTER_DUMP // Adds gyroregisters command to cli to dump configured register values
218 #define USE_IMU_CALC
219 #define USE_PPM
220 #define USE_SERIAL_RX
221 #define USE_SERIALRX_CRSF // Team Black Sheep Crossfire protocol
222 #define USE_SERIALRX_GHST // ImmersionRC Ghost Protocol
223 #define USE_SERIALRX_IBUS // FlySky and Turnigy receivers
224 #define USE_SERIALRX_SBUS // Frsky and Futaba receivers
225 #define USE_SERIALRX_SPEKTRUM // SRXL, DSM2 and DSMX protocol
226 #define USE_SERIALRX_SUMD // Graupner Hott protocol
228 #if (TARGET_FLASH_SIZE > 128)
229 #define PID_PROFILE_COUNT 3
230 #define CONTROL_RATE_PROFILE_COUNT 6
231 #else
232 #define PID_PROFILE_COUNT 2
233 #define CONTROL_RATE_PROFILE_COUNT 3
234 #endif
236 #if (TARGET_FLASH_SIZE > 64)
237 #define USE_ACRO_TRAINER
238 #define USE_BLACKBOX
239 #define USE_CLI_BATCH
240 #define USE_RESOURCE_MGMT
241 #define USE_RUNAWAY_TAKEOFF // Runaway Takeoff Prevention (anti-taz)
242 #define USE_SERVOS
243 #define USE_TELEMETRY
244 #define USE_TELEMETRY_FRSKY_HUB
245 #define USE_TELEMETRY_SMARTPORT
246 #endif
248 #if (TARGET_FLASH_SIZE > 128)
249 #define USE_GYRO_OVERFLOW_CHECK
250 #define USE_YAW_SPIN_RECOVERY
251 #define USE_DSHOT_DMAR
252 #define USE_SERIALRX_FPORT // FrSky FPort
253 #define USE_TELEMETRY_CRSF
254 #define USE_TELEMETRY_GHST
255 #define USE_TELEMETRY_SRXL
257 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 12))
258 #define USE_CMS
259 #define USE_MSP_DISPLAYPORT
260 #define USE_MSP_OVER_TELEMETRY
261 #define USE_OSD_OVER_MSP_DISPLAYPORT
262 #define USE_LED_STRIP
263 #endif
265 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 11))
266 #define USE_VTX_COMMON
267 #define USE_VTX_CONTROL
268 #define USE_VTX_SMARTAUDIO
269 #define USE_VTX_TRAMP
270 #endif
272 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 10))
273 #define USE_VIRTUAL_CURRENT_METER
274 #define USE_CAMERA_CONTROL
275 #define USE_ESC_SENSOR
276 #define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
277 #define USE_RCDEVICE
278 #endif
280 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 9))
281 #define USE_GYRO_LPF2
282 #endif
284 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 8))
285 #define USE_LAUNCH_CONTROL
286 #define USE_DYN_LPF
287 #define USE_D_MIN
288 #endif
290 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 7))
291 #define USE_THROTTLE_BOOST
292 #define USE_INTEGRATED_YAW_CONTROL
293 #endif
295 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 6))
296 #define USE_ITERM_RELAX
297 #define USE_RC_SMOOTHING_FILTER
298 #define USE_THRUST_LINEARIZATION
299 #define USE_TPA_MODE
300 #endif
302 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 5))
303 #define USE_PWM
304 #endif
306 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 4))
307 #define USE_HUFFMAN
308 #define USE_PINIO
309 #define USE_PINIOBOX
310 #endif
312 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 3))
313 #ifdef USE_SERIALRX_SPEKTRUM
314 #define USE_SPEKTRUM_BIND
315 #define USE_SPEKTRUM_BIND_PLUG
316 #define USE_SPEKTRUM_REAL_RSSI
317 #define USE_SPEKTRUM_FAKE_RSSI
318 #define USE_SPEKTRUM_RSSI_PERCENT_CONVERSION
319 #define USE_SPEKTRUM_VTX_CONTROL
320 #define USE_SPEKTRUM_VTX_TELEMETRY
321 #define USE_SPEKTRUM_CMS_TELEMETRY
322 #define USE_PIN_PULL_UP_DOWN
323 #endif
324 #endif
326 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 2))
327 #define USE_TELEMETRY_HOTT
328 #define USE_TELEMETRY_LTM
329 #define USE_SERIALRX_SUMH // Graupner legacy protocol
330 #define USE_SERIALRX_XBUS // JR
331 #endif
333 #if ((TARGET_FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 1))
334 #define USE_BOARD_INFO
335 #define USE_EXTENDED_CMS_MENUS
336 #define USE_RTC_TIME
337 #define USE_RX_MSP
338 #define USE_ESC_SENSOR_INFO
339 #define USE_CRSF_CMS_TELEMETRY
340 #define USE_CRSF_LINK_STATISTICS
341 #define USE_RX_RSSI_DBM
342 #endif
344 #endif // TARGET_FLASH_SIZE > 128
346 #if (TARGET_FLASH_SIZE > 256)
347 #define USE_AIRMODE_LPF
348 #define USE_CANVAS
349 #define USE_DASHBOARD
350 #define USE_FRSKYOSD
351 #define USE_GPS
352 #define USE_GPS_NMEA
353 #define USE_GPS_UBLOX
354 #define USE_GPS_RESCUE
355 #define USE_GYRO_DLPF_EXPERIMENTAL
356 #define USE_OSD
357 #define USE_OSD_OVER_MSP_DISPLAYPORT
358 #define USE_MULTI_GYRO
359 #define USE_OSD_ADJUSTMENTS
360 #define USE_SENSOR_NAMES
361 #define USE_SERIALRX_JETIEXBUS
362 #define USE_TELEMETRY_IBUS
363 #define USE_TELEMETRY_IBUS_EXTENDED
364 #define USE_TELEMETRY_JETIEXBUS
365 #define USE_TELEMETRY_MAVLINK
366 #define USE_UNCOMMON_MIXERS
367 #define USE_SIGNATURE
368 #define USE_ABSOLUTE_CONTROL
369 #define USE_HOTT_TEXTMODE
370 #define USE_LED_STRIP_STATUS_MODE
371 #define USE_VARIO
372 #define USE_RX_LINK_QUALITY_INFO
373 #define USE_ESC_SENSOR_TELEMETRY
374 #define USE_OSD_PROFILES
375 #define USE_OSD_STICK_OVERLAY
376 #define USE_ESCSERIAL_SIMONK
377 #define USE_SERIAL_4WAY_SK_BOOTLOADER
378 #define USE_CMS_FAILSAFE_MENU
379 #define USE_CMS_GPS_RESCUE_MENU
380 #define USE_TELEMETRY_SENSORS_DISABLED_DETAILS
381 #define USE_VTX_TABLE
382 #define USE_PERSISTENT_STATS
383 #define USE_PROFILE_NAMES
384 #define USE_SERIALRX_SRXL2 // Spektrum SRXL2 protocol
385 #define USE_INTERPOLATED_SP
386 #define USE_CUSTOM_BOX_NAMES
387 #define USE_BATTERY_VOLTAGE_SAG_COMPENSATION
388 #define USE_RX_MSP_OVERRIDE
389 #define USE_SIMPLIFIED_TUNING
390 #define USE_RX_LINK_UPLINK_POWER
391 #define USE_GPS_PLUS_CODES
392 #endif