Paparazzi UAS  v5.18.0_stable
Paparazzi is a free software Unmanned Aircraft System.
px4fmu_2.4.h
Go to the documentation of this file.
1 #ifndef CONFIG_PX4FMU_2_4_H
2 #define CONFIG_PX4FMU_2_4_H
3 
4 #define BOARD_PX4FMU_v2
5 
6 /* Pixhawk board (PX4FMUv2 has a 24MHz external clock and 168MHz internal. */
7 //STM32F4
8 #define EXT_CLK 24000000
9 #define AHB_CLK 168000000
10 
11 /*
12  * Onboard LEDs
13  */
14 /* red, on PE12 */
15 #ifndef USE_LED_1
16 #define USE_LED_1 1
17 #endif
18 #define LED_1_GPIO GPIOE
19 #define LED_1_GPIO_PIN GPIO12
20 #define LED_1_GPIO_ON gpio_clear
21 #define LED_1_GPIO_OFF gpio_set
22 #define LED_1_AFIO_REMAP ((void)0)
23 
24 /*
25  * UART
26 */
27 
28 // conector telem1
29 #define UART2_GPIO_AF GPIO_AF7
30 #define UART2_GPIO_PORT_RX GPIOD
31 #define UART2_GPIO_RX GPIO6
32 #define UART2_GPIO_PORT_TX GPIOD
33 #define UART2_GPIO_TX GPIO5
34 //#define UART2_CTS PD3
35 //#define UART2_RTS PD4
36 
37 //conector telem2
38 #define UART3_GPIO_AF GPIO_AF7
39 #define UART3_GPIO_PORT_RX GPIOD
40 #define UART3_GPIO_RX GPIO9
41 #define UART3_GPIO_PORT_TX GPIOD
42 #define UART3_GPIO_TX GPIO8
43 //CTS - P11
44 //RTS - P12
45 
46 //GPS
47 #define UART4_GPIO_AF GPIO_AF8
48 #define UART4_GPIO_PORT_RX GPIOA
49 #define UART4_GPIO_RX GPIO1
50 #define UART4_GPIO_PORT_TX GPIOA
51 #define UART4_GPIO_TX GPIO0
52 
53 //debug ligado no processador IO
54 #define UART6_GPIO_AF GPIO_AF8
55 #define UART6_GPIO_PORT_RX GPIOC
56 #define UART6_GPIO_RX GPIO7
57 #define UART6_GPIO_PORT_TX GPIOC
58 #define UART6_GPIO_TX GPIO6
59 
60 //conector serial5
61 #define UART7_GPIO_AF GPIO_AF8
62 #define UART7_GPIO_PORT_RX GPIOE
63 #define UART7_GPIO_RX GPIO7
64 #define UART7_GPIO_PORT_TX GPIOE
65 #define UART7_GPIO_TX GPIO8
66 
67 //conector serial4
68 #define UART8_GPIO_AF GPIO_AF8
69 #define UART8_GPIO_PORT_RX GPIOE
70 #define UART8_GPIO_RX GPIO0
71 #define UART8_GPIO_PORT_TX GPIOE
72 #define UART8_GPIO_TX GPIO1
73 
74 /*
75  * SPI
76  */
77 
78 /* SPI1 for MPU and accel/gyro if populated */
79 #define SPI1_GPIO_AF GPIO_AF5
80 #define SPI1_GPIO_PORT_MISO GPIOA
81 #define SPI1_GPIO_MISO GPIO6
82 #define SPI1_GPIO_PORT_MOSI GPIOA
83 #define SPI1_GPIO_MOSI GPIO7
84 #define SPI1_GPIO_PORT_SCK GPIOA
85 #define SPI1_GPIO_SCK GPIO5
86 
87 /* SPI2 for FRAM */
88 #define SPI2_GPIO_AF GPIO_AF5
89 #define SPI2_GPIO_PORT_MISO GPIOB
90 #define SPI2_GPIO_MISO GPIO14
91 #define SPI2_GPIO_PORT_MOSI GPIOB
92 #define SPI2_GPIO_MOSI GPIO15
93 #define SPI2_GPIO_PORT_SCK GPIOB
94 #define SPI2_GPIO_SCK GPIO13
95 
96 /* SPI4 Ext SPI connector */
97 #define SPI4_GPIO_AF GPIO_AF5
98 #define SPI4_GPIO_PORT_MISO GPIOE
99 #define SPI4_GPIO_MISO GPIO5
100 #define SPI4_GPIO_PORT_MOSI GPIOE
101 #define SPI4_GPIO_MOSI GPIO6
102 #define SPI4_GPIO_PORT_SCK GPIOE
103 #define SPI4_GPIO_SCK GPIO2
104 
105 /*
106  * SPI slave pin declaration
107  */
108 /* GYRO_CS on SPI1 */
109 #define SPI_SELECT_SLAVE0_PORT GPIOC
110 #define SPI_SELECT_SLAVE0_PIN GPIO13
111 
112 /* ACCEL_MAG_CS on SPI1 */
113 #define SPI_SELECT_SLAVE1_PORT GPIOC
114 #define SPI_SELECT_SLAVE1_PIN GPIO15
115 
116 /* MPU_CS on SPI1 */
117 #define SPI_SELECT_SLAVE2_PORT GPIOC
118 #define SPI_SELECT_SLAVE2_PIN GPIO2
119 
120 /* BARO_CS on SPI1 */
121 #define SPI_SELECT_SLAVE3_PORT GPIOD
122 #define SPI_SELECT_SLAVE3_PIN GPIO7
123 
124 /* FRAM_CS on SPI2 */
125 #define SPI_SELECT_SLAVE4_PORT GPIOD
126 #define SPI_SELECT_SLAVE4_PIN GPIO10
127 
128 /* MAG_CS on SPI1 */
129 #define SPI_SELECT_SLAVE5_PORT GPIOC
130 #define SPI_SELECT_SLAVE5_PIN GPIO1
131 
132 /* SPI3 NSS on microSD connector */
133 /*
134 #define SPI_SELECT_SLAVE3_PORT GPIOA
135 #define SPI_SELECT_SLAVE3_PIN GPIO4
136 */
137 
138 // SDIO on microSD connector
139 //#define SDIO_AF GPIO_AF12
140 // SDIO_D0 pc8
141 // SDIO_D1 pc9
142 // SDIO_D2 pc10
143 // SDIO_D3 pc11
144 // SDIO_CK pc12
145 // SDIO_CMD pd2
146 
147 /* Onboard ADCs */
148 
149 #if USE_AD_TIM2
150 #undef USE_AD_TIM2 // timer2 is used by the buzzer
151 #endif
152 #define USE_AD_TIM3 1
153 
154 // Interal ADC for battery
155 #ifndef USE_ADC_1
156 #define USE_ADC_1 1
157 #endif
158 #if USE_ADC_1
159 #define AD1_1_CHANNEL 4 //ADC12_IN4
160 #define ADC_1 AD1_1
161 #define ADC_1_GPIO_PORT GPIOA
162 #define ADC_1_GPIO_PIN GPIO4
163 #endif
164 
165 // External ADC for battery
166 #ifndef USE_ADC_2
167 #define USE_ADC_2 1
168 #endif
169 #if USE_ADC_2
170 #define AD1_2_CHANNEL 2 // ADC123_IN2 (--> IN2 corresponds to channel 2)
171 #define ADC_2 AD1_2 // ADC123 means it can be used by ADC 1 and 2 and 3 (the f4 supports 3 adc's), does not matter which. Each ADC can address 4 pins, so in this case we are using ADC 1, on its second pin.
172 #define ADC_2_GPIO_PORT GPIOA
173 #define ADC_2_GPIO_PIN GPIO2
174 #endif
175 
176 // external current sens
177 #ifndef USE_ADC_3
178 #define USE_ADC_3 1
179 #endif
180 #if USE_ADC_3
181 #define AD1_3_CHANNEL 3 // ADC123_IN3
182 #define ADC_3 AD1_3
183 #define ADC_3_GPIO_PORT GPIOA
184 #define ADC_3_GPIO_PIN GPIO3
185 #endif
186 #define MilliAmpereOfAdc(adc)((float)adc) * (3.3f / 4096.0f) * (90.0f / 5.0f)
187 
188 /* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/
189 #ifndef ADC_CHANNEL_VSUPPLY
190 #define ADC_CHANNEL_VSUPPLY ADC_2
191 #define DefaultVoltageOfAdc(adc) (0.00975*adc)
192 #else
193 #define DefaultVoltageOfAdc(adc) (0.00384*adc)
194 #endif
195 
196 /* External adc (pressure / air speed / 6.6v) */
197 #ifndef USE_ADC_4
198 #define USE_ADC_4 1
199 #endif
200 #if USE_ADC_4
201 #define AD1_4_CHANNEL 15 // ADC12_IN15
202 #define ADC_4 AD1_4
203 #define ADC_4_GPIO_PORT GPIOC
204 #define ADC_4_GPIO_PIN GPIO5
205 #endif
206 
207 /* External adc 3.3v */
208 #if USE_ADC_5
209 #define AD1_5_CHANNEL 13 // ADC123_IN13
210 #define ADC_5 AD1_5
211 #define ADC_5_GPIO_PORT GPIOC
212 #define ADC_5_GPIO_PIN GPIO3
213 #endif
214 
215 /* External adc 3.3v */
216 #if USE_ADC_6
217 #define AD1_6_CHANNEL 14 // ADC12_IN14
218 #define ADC_6 AD1_6
219 #define ADC_6_GPIO_PORT GPIOC
220 #define ADC_6_GPIO_PIN GPIO4
221 #endif
222 
223 /*
224  * I2C mapping
225  */
226 #define I2C1_GPIO_PORT GPIOB
227 #define I2C1_GPIO_SCL GPIO8
228 #define I2C1_GPIO_SDA GPIO9
229 
230 #define I2C2_GPIO_PORT GPIOB
231 #define I2C2_GPIO_SCL GPIO10
232 #define I2C2_GPIO_SDA GPIO11
233 
234 /*
235 #define I2C3_GPIO_PORT_SCL GPIOA
236 #define I2C3_GPIO_SCL GPIO8
237 #define I2C3_GPIO_PORT_SDA GPIOC
238 #define I2C3_GPIO_SDA GPIO9
239 */
240 
241 /* Activate onboard baro by default */
242 #ifndef USE_BARO_BOARD
243 #define USE_BARO_BOARD 1
244 #endif
245 
246 
247 /* Default actuators driver */
248 #define DEFAULT_ACTUATORS "subsystems/actuators/actuators_pwm.h"
249 #define ActuatorDefaultSet(_x,_y) ActuatorPwmSet(_x,_y)
250 #define ActuatorsDefaultInit() ActuatorsPwmInit()
251 #define ActuatorsDefaultCommit() ActuatorsPwmCommit()
252 
253 /* PWM */
254 #define PWM_USE_TIM1 1
255 #define PWM_USE_TIM4 1
256 
257 #define USE_PWM1 1
258 #define USE_PWM2 1
259 #define USE_PWM3 1
260 #define USE_PWM4 1
261 #define USE_PWM5 1
262 #define USE_PWM6 1
263 //#define USE_BUZZER 1
264 
265 // Servo numbering on the PX4 starts with 1
266 // PWM_SERVO_x is the index of the servo in the actuators_pwm_values array
267 
268 //servo AUX1
269 #if USE_PWM1
270 #define PWM_SERVO_1 0
271 #define PWM_SERVO_1_TIMER TIM1
272 #define PWM_SERVO_1_GPIO GPIOE
273 #define PWM_SERVO_1_PIN GPIO14
274 #define PWM_SERVO_1_AF GPIO_AF1
275 #define PWM_SERVO_1_OC TIM_OC4
276 #define PWM_SERVO_1_OC_BIT (1<<3)
277 #else
278 #define PWM_SERVO_1_OC_BIT 0
279 #endif
280 
281 //servo AUX2
282 #if USE_PWM2
283 #define PWM_SERVO_2 1
284 #define PWM_SERVO_2_TIMER TIM1
285 #define PWM_SERVO_2_GPIO GPIOE
286 #define PWM_SERVO_2_PIN GPIO13
287 #define PWM_SERVO_2_AF GPIO_AF1
288 #define PWM_SERVO_2_OC TIM_OC3
289 #define PWM_SERVO_2_OC_BIT (1<<2)
290 #else
291 #define PWM_SERVO_2_OC_BIT 0
292 #endif
293 
294 //servo AUX3
295 #if USE_PWM3
296 #define PWM_SERVO_3 2 //#define PWM_SERVO_3_IDX 2
297 #define PWM_SERVO_3_TIMER TIM1
298 #define PWM_SERVO_3_GPIO GPIOE
299 #define PWM_SERVO_3_PIN GPIO11
300 #define PWM_SERVO_3_AF GPIO_AF1
301 #define PWM_SERVO_3_OC TIM_OC2
302 #define PWM_SERVO_3_OC_BIT (1<<1)
303 #else
304 #define PWM_SERVO_3_OC_BIT 0
305 #endif
306 
307 //servo AUX4
308 #if USE_PWM4
309 #define PWM_SERVO_4 3
310 #define PWM_SERVO_4_TIMER TIM1
311 #define PWM_SERVO_4_GPIO GPIOE
312 #define PWM_SERVO_4_PIN GPIO9
313 #define PWM_SERVO_4_AF GPIO_AF1
314 #define PWM_SERVO_4_OC TIM_OC1
315 #define PWM_SERVO_4_OC_BIT (1<<0)
316 #else
317 #define PWM_SERVO_4_OC_BIT 0
318 #endif
319 
320 //servo AUX5
321 #if USE_PWM5
322 #define PWM_SERVO_5 4
323 #define PWM_SERVO_5_TIMER TIM4
324 #define PWM_SERVO_5_GPIO GPIOD
325 #define PWM_SERVO_5_PIN GPIO13
326 #define PWM_SERVO_5_AF GPIO_AF2
327 #define PWM_SERVO_5_OC TIM_OC2
328 #define PWM_SERVO_5_OC_BIT (1<<1)
329 #else
330 #define PWM_SERVO_5_OC_BIT 0
331 #endif
332 
333 //servo AUX6
334 #if USE_PWM6
335 #define PWM_SERVO_6 5
336 #define PWM_SERVO_6_TIMER TIM4
337 #define PWM_SERVO_6_GPIO GPIOD
338 #define PWM_SERVO_6_PIN GPIO14
339 #define PWM_SERVO_6_AF GPIO_AF2
340 #define PWM_SERVO_6_OC TIM_OC3
341 #define PWM_SERVO_6_OC_BIT (1<<2)
342 #else
343 #define PWM_SERVO_6_OC_BIT 0
344 #endif
345 
346 //Buzzer (alarm)
347 #if USE_BUZZER
348 #define PWM_BUZZER
349 #define PWM_BUZZER_TIMER TIM2
350 #define PWM_BUZZER_GPIO GPIOA
351 #define PWM_BUZZER_PIN GPIO15
352 #define PWM_BUZZER_AF GPIO_AF1
353 #define PWM_BUZZER_OC TIM_OC1
354 #define PWM_BUZZER_OC_BIT (1<<0)
355 #define PWM_TIM2_CHAN_MASK (PWM_BUZZER_OC_BIT)
356 #else
357 #define PWM_BUZZER_OC_BIT 0
358 #endif
359 
360 #define PWM_TIM1_CHAN_MASK (PWM_SERVO_1_OC_BIT|PWM_SERVO_2_OC_BIT|PWM_SERVO_3_OC_BIT|PWM_SERVO_4_OC_BIT)
361 #define PWM_TIM4_CHAN_MASK (PWM_SERVO_5_OC_BIT|PWM_SERVO_6_OC_BIT)
362 
363 #endif /* CONFIG_PX4FMU_2_4_H */