Added support for F411, F446, F745, F765.
[betaflight.git] / src / main / target / common_pre.h
blob8a145fd2f75b4435168e11c9364b41587510596d
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
32 #define DEBUG_MODE DEBUG_NONE // change this to change initial debug mode
34 #define I2C1_OVERCLOCK true
35 #define I2C2_OVERCLOCK true
37 #ifdef STM32F1
38 #define MINIMAL_CLI
39 // Using RX DMA disables the use of receive callbacks
40 #define USE_UART1_RX_DMA
41 #define USE_UART1_TX_DMA
42 #endif
44 #ifdef STM32F3
45 #define MINIMAL_CLI
46 #define USE_DSHOT
47 #define USE_GYRO_DATA_ANALYSE
48 #endif
50 #ifdef STM32F4
51 #define USE_SRAM2
52 #if defined(STM32F40_41xxx)
53 #define USE_FAST_RAM
54 #endif
55 #define USE_DSHOT
56 #define USE_DSHOT_TELEMETRY
57 #define USE_RPM_FILTER
58 #define I2C3_OVERCLOCK true
59 #define USE_GYRO_DATA_ANALYSE
60 #define USE_ADC
61 #define USE_ADC_INTERNAL
62 #define USE_USB_CDC_HID
63 #define USE_USB_MSC
64 #define USE_PERSISTENT_MSC_RTC
65 #define USE_DMA_SPEC
66 #define USE_TIMER_MGMT
67 // Re-enable this after 4.0 has been released, and remove the define from STM32F4DISCOVERY
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_SRAM2
78 #define USE_ITCM_RAM
79 #define USE_FAST_RAM
80 #define USE_DSHOT
81 #define I2C3_OVERCLOCK true
82 #define I2C4_OVERCLOCK true
83 #define USE_GYRO_DATA_ANALYSE
84 #define USE_OVERCLOCK
85 #define USE_ADC_INTERNAL
86 #define USE_USB_CDC_HID
87 #define USE_USB_MSC
88 #define USE_PERSISTENT_MSC_RTC
89 #define USE_MCO
90 #define USE_DMA_SPEC
91 #define USE_TIMER_MGMT
92 // Re-enable this after 4.0 has been released, and remove the define from STM32F4DISCOVERY
93 //#define USE_SPI_TRANSACTION
94 #endif // STM32F7
96 #if defined(STM32F4) || defined(STM32F7)
97 #define TASK_GYROPID_DESIRED_PERIOD 125 // 125us = 8kHz
98 #define SCHEDULER_DELAY_LIMIT 10
99 #else
100 #define TASK_GYROPID_DESIRED_PERIOD 1000 // 1000us = 1kHz
101 #define SCHEDULER_DELAY_LIMIT 100
102 #endif
104 #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
105 #define DEFAULT_AUX_CHANNEL_COUNT MAX_AUX_CHANNEL_COUNT
106 #else
107 #define DEFAULT_AUX_CHANNEL_COUNT 6
108 #endif
110 #ifdef USE_ITCM_RAM
111 #define FAST_CODE __attribute__((section(".tcm_code")))
112 #define FAST_CODE_NOINLINE NOINLINE
113 #else
114 #define FAST_CODE
115 #define FAST_CODE_NOINLINE
116 #endif // USE_ITCM_RAM
118 #ifdef USE_FAST_RAM
119 #define FAST_RAM_ZERO_INIT __attribute__ ((section(".fastram_bss"), aligned(4)))
120 #define FAST_RAM __attribute__ ((section(".fastram_data"), aligned(4)))
121 #else
122 #define FAST_RAM_ZERO_INIT
123 #define FAST_RAM
124 #endif // USE_FAST_RAM
126 #ifdef STM32F4
127 // Data in RAM which is guaranteed to not be reset on hot reboot
128 #define PERSISTENT __attribute__ ((section(".persistent_data"), aligned(4)))
129 #endif
131 #ifdef USE_SRAM2
132 #define SRAM2 __attribute__ ((section(".sram2"), aligned(4)))
133 #else
134 #define SRAM2
135 #endif
137 #define USE_BRUSHED_ESC_AUTODETECT // Detect if brushed motors are connected and set defaults appropriately to avoid motors spinning on boot
139 #define USE_CLI
140 #define USE_SERIAL_PASSTHROUGH
141 #define USE_TASK_STATISTICS
142 #define USE_GYRO_REGISTER_DUMP // Adds gyroregisters command to cli to dump configured register values
143 #define USE_IMU_CALC
144 #define USE_PPM
145 #define USE_SERIAL_RX
146 #define USE_SERIALRX_CRSF // Team Black Sheep Crossfire protocol
147 #define USE_SERIALRX_IBUS // FlySky and Turnigy receivers
148 #define USE_SERIALRX_SBUS // Frsky and Futaba receivers
149 #define USE_SERIALRX_SPEKTRUM // SRXL, DSM2 and DSMX protocol
150 #define USE_SERIALRX_SUMD // Graupner Hott protocol
152 #if (FLASH_SIZE > 128)
153 #define PID_PROFILE_COUNT 3
154 #define CONTROL_RATE_PROFILE_COUNT 6
155 #else
156 #define PID_PROFILE_COUNT 2
157 #define CONTROL_RATE_PROFILE_COUNT 3
158 #endif
160 #if (FLASH_SIZE > 64)
161 #define USE_ACRO_TRAINER
162 #define USE_BLACKBOX
163 #define USE_RESOURCE_MGMT
164 #define USE_RUNAWAY_TAKEOFF // Runaway Takeoff Prevention (anti-taz)
165 #define USE_SERVOS
166 #define USE_TELEMETRY
167 #define USE_TELEMETRY_FRSKY_HUB
168 #define USE_TELEMETRY_SMARTPORT
169 #endif
171 #if (FLASH_SIZE > 128)
172 #define USE_GYRO_OVERFLOW_CHECK
173 #define USE_YAW_SPIN_RECOVERY
174 #define USE_DSHOT_DMAR
175 #define USE_SERIALRX_FPORT // FrSky FPort
176 #define USE_TELEMETRY_CRSF
177 #define USE_TELEMETRY_SRXL
179 #if ((FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 12))
180 #define USE_CMS
181 #define USE_MSP_DISPLAYPORT
182 #define USE_MSP_OVER_TELEMETRY
183 #define USE_LED_STRIP
184 #endif
186 #if ((FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 11))
187 #define USE_VTX_COMMON
188 #define USE_VTX_CONTROL
189 #define USE_VTX_SMARTAUDIO
190 #define USE_VTX_TRAMP
191 #endif
193 #if ((FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 10))
194 #define USE_VIRTUAL_CURRENT_METER
195 #define USE_CAMERA_CONTROL
196 #define USE_ESC_SENSOR
197 #define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
198 #define USE_RCDEVICE
199 #endif
201 #if ((FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 9))
202 #define USE_GYRO_LPF2
203 #endif
205 #if ((FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 8))
206 #define USE_LAUNCH_CONTROL
207 #define USE_DYN_LPF
208 #define USE_D_MIN
209 #endif
211 #if ((FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 7))
212 #define USE_THROTTLE_BOOST
213 #define USE_INTEGRATED_YAW_CONTROL
214 #endif
216 #if ((FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 6))
217 #define USE_ITERM_RELAX
218 #define USE_RC_SMOOTHING_FILTER
219 #define USE_THRUST_LINEARIZATION
220 #define USE_TPA_MODE
221 #endif
223 #if ((FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 5))
224 #define USE_PWM
225 #endif
227 #if ((FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 4))
228 #define USE_HUFFMAN
229 #define USE_PINIO
230 #define USE_PINIOBOX
231 #endif
233 #if ((FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 3))
234 #ifdef USE_SERIALRX_SPEKTRUM
235 #define USE_SPEKTRUM_BIND
236 #define USE_SPEKTRUM_BIND_PLUG
237 #define USE_SPEKTRUM_REAL_RSSI
238 #define USE_SPEKTRUM_FAKE_RSSI
239 #define USE_SPEKTRUM_RSSI_PERCENT_CONVERSION
240 #define USE_SPEKTRUM_VTX_CONTROL
241 #define USE_SPEKTRUM_VTX_TELEMETRY
242 #define USE_SPEKTRUM_CMS_TELEMETRY
243 #endif
244 #endif
246 #if ((FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 2))
247 #define USE_TELEMETRY_HOTT
248 #define USE_TELEMETRY_LTM
249 #define USE_SERIALRX_SUMH // Graupner legacy protocol
250 #define USE_SERIALRX_XBUS // JR
251 #endif
253 #if ((FLASH_SIZE > 256) || (FEATURE_CUT_LEVEL < 1))
254 #define USE_BOARD_INFO
255 #define USE_EXTENDED_CMS_MENUS
256 #define USE_RTC_TIME
257 #define USE_RX_MSP
258 #define USE_ESC_SENSOR_INFO
259 #define USE_CRSF_CMS_TELEMETRY
260 #endif
262 #endif // FLASH_SIZE > 128
264 #if (FLASH_SIZE > 256)
265 #define USE_AIRMODE_LPF
266 #define USE_DASHBOARD
267 #define USE_GPS
268 #define USE_GPS_NMEA
269 #define USE_GPS_UBLOX
270 #define USE_GPS_RESCUE
271 #define USE_GYRO_DLPF_EXPERIMENTAL
272 #define USE_OSD
273 #define USE_OSD_OVER_MSP_DISPLAYPORT
274 #define USE_MULTI_GYRO
275 #define USE_OSD_ADJUSTMENTS
276 #define USE_SENSOR_NAMES
277 #define USE_SERIALRX_JETIEXBUS
278 #define USE_TELEMETRY_IBUS
279 #define USE_TELEMETRY_IBUS_EXTENDED
280 #define USE_TELEMETRY_JETIEXBUS
281 #define USE_TELEMETRY_MAVLINK
282 #define USE_UNCOMMON_MIXERS
283 #define USE_SIGNATURE
284 #define USE_ABSOLUTE_CONTROL
285 #define USE_HOTT_TEXTMODE
286 #define USE_LED_STRIP_STATUS_MODE
287 #define USE_VARIO
288 #define USE_RX_LINK_QUALITY_INFO
289 #define USE_ESC_SENSOR_TELEMETRY
290 #define USE_OSD_PROFILES
291 #define USE_OSD_STICK_OVERLAY
292 #define USE_ESCSERIAL_SIMONK
293 #define USE_SERIAL_4WAY_SK_BOOTLOADER
294 #define USE_CMS_FAILSAFE_MENU
295 #define USE_SMART_FEEDFORWARD
296 #define USE_TELEMETRY_SENSORS_DISABLED_DETAILS
297 // Re-enable this after 4.0 has been released, and remove the define from STM32F4DISCOVERY
298 //#define USE_VTX_TABLE
299 #endif