Paparazzi UAS  v5.14.0_stable-0-g3f680d1
Paparazzi is a free software Unmanned Aircraft System.
 All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Modules Pages
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 /* SPI3 NSS on microSD connector */
129 /*
130 #define SPI_SELECT_SLAVE3_PORT GPIOA
131 #define SPI_SELECT_SLAVE3_PIN GPIO4
132 */
133 
134 // SDIO on microSD connector
135 //#define SDIO_AF GPIO_AF12
136 // SDIO_D0 pc8
137 // SDIO_D1 pc9
138 // SDIO_D2 pc10
139 // SDIO_D3 pc11
140 // SDIO_CK pc12
141 // SDIO_CMD pd2
142 
143 /* Onboard ADCs */
144 
145 #if USE_AD_TIM2
146 #undef USE_AD_TIM2 // timer2 is used by the buzzer
147 #endif
148 #define USE_AD_TIM3 1
149 
150 // Interal ADC for battery
151 #ifndef USE_ADC_1
152 #define USE_ADC_1 1
153 #endif
154 #if USE_ADC_1
155 #define AD1_1_CHANNEL 4 //ADC12_IN4
156 #define ADC_1 AD1_1
157 #define ADC_1_GPIO_PORT GPIOA
158 #define ADC_1_GPIO_PIN GPIO4
159 #endif
160 
161 // External ADC for battery
162 #ifndef USE_ADC_2
163 #define USE_ADC_2 1
164 #endif
165 #if USE_ADC_2
166 #define AD1_2_CHANNEL 2 // ADC123_IN2 (--> IN2 corresponds to channel 2)
167 #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.
168 #define ADC_2_GPIO_PORT GPIOA
169 #define ADC_2_GPIO_PIN GPIO2
170 #endif
171 
172 // external current sens
173 #ifndef USE_ADC_3
174 #define USE_ADC_3 1
175 #endif
176 #if USE_ADC_3
177 #define AD1_3_CHANNEL 3 // ADC123_IN3
178 #define ADC_3 AD1_3
179 #define ADC_3_GPIO_PORT GPIOA
180 #define ADC_3_GPIO_PIN GPIO3
181 #endif
182 #define MilliAmpereOfAdc(adc)((float)adc) * (3.3f / 4096.0f) * (90.0f / 5.0f)
183 
184 /* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/
185 #ifndef ADC_CHANNEL_VSUPPLY
186 #define ADC_CHANNEL_VSUPPLY ADC_2
187 #define DefaultVoltageOfAdc(adc) (0.00975*adc)
188 #else
189 #define DefaultVoltageOfAdc(adc) (0.00384*adc)
190 #endif
191 
192 /* External adc (pressure / air speed / 6.6v) */
193 #ifndef USE_ADC_4
194 #define USE_ADC_4 1
195 #endif
196 #if USE_ADC_4
197 #define AD1_4_CHANNEL 15 // ADC12_IN15
198 #define ADC_4 AD1_4
199 #define ADC_4_GPIO_PORT GPIOC
200 #define ADC_4_GPIO_PIN GPIO5
201 #endif
202 
203 /* External adc 3.3v */
204 #if USE_ADC_5
205 #define AD1_5_CHANNEL 13 // ADC123_IN13
206 #define ADC_5 AD1_5
207 #define ADC_5_GPIO_PORT GPIOC
208 #define ADC_5_GPIO_PIN GPIO3
209 #endif
210 
211 /* External adc 3.3v */
212 #if USE_ADC_6
213 #define AD1_6_CHANNEL 14 // ADC12_IN14
214 #define ADC_6 AD1_6
215 #define ADC_6_GPIO_PORT GPIOC
216 #define ADC_6_GPIO_PIN GPIO4
217 #endif
218 
219 /*
220  * I2C mapping
221  */
222 #define I2C1_GPIO_PORT GPIOB
223 #define I2C1_GPIO_SCL GPIO8
224 #define I2C1_GPIO_SDA GPIO9
225 
226 #define I2C2_GPIO_PORT GPIOB
227 #define I2C2_GPIO_SCL GPIO10
228 #define I2C2_GPIO_SDA GPIO11
229 
230 /*
231 #define I2C3_GPIO_PORT_SCL GPIOA
232 #define I2C3_GPIO_SCL GPIO8
233 #define I2C3_GPIO_PORT_SDA GPIOC
234 #define I2C3_GPIO_SDA GPIO9
235 */
236 
237 /* Activate onboard baro by default */
238 #ifndef USE_BARO_BOARD
239 #define USE_BARO_BOARD 1
240 #endif
241 
242 
243 /* Default actuators driver */
244 #define DEFAULT_ACTUATORS "subsystems/actuators/actuators_pwm.h"
245 #define ActuatorDefaultSet(_x,_y) ActuatorPwmSet(_x,_y)
246 #define ActuatorsDefaultInit() ActuatorsPwmInit()
247 #define ActuatorsDefaultCommit() ActuatorsPwmCommit()
248 
249 /* PWM */
250 #define PWM_USE_TIM1 1
251 #define PWM_USE_TIM4 1
252 
253 #define USE_PWM1 1
254 #define USE_PWM2 1
255 #define USE_PWM3 1
256 #define USE_PWM4 1
257 #define USE_PWM5 1
258 #define USE_PWM6 1
259 //#define USE_BUZZER 1
260 
261 // Servo numbering on the PX4 starts with 1
262 // PWM_SERVO_x is the index of the servo in the actuators_pwm_values array
263 
264 //servo AUX1
265 #if USE_PWM1
266 #define PWM_SERVO_1 0
267 #define PWM_SERVO_1_TIMER TIM1
268 #define PWM_SERVO_1_GPIO GPIOE
269 #define PWM_SERVO_1_PIN GPIO14
270 #define PWM_SERVO_1_AF GPIO_AF1
271 #define PWM_SERVO_1_OC TIM_OC4
272 #define PWM_SERVO_1_OC_BIT (1<<3)
273 #else
274 #define PWM_SERVO_1_OC_BIT 0
275 #endif
276 
277 //servo AUX2
278 #if USE_PWM2
279 #define PWM_SERVO_2 1
280 #define PWM_SERVO_2_TIMER TIM1
281 #define PWM_SERVO_2_GPIO GPIOE
282 #define PWM_SERVO_2_PIN GPIO13
283 #define PWM_SERVO_2_AF GPIO_AF1
284 #define PWM_SERVO_2_OC TIM_OC3
285 #define PWM_SERVO_2_OC_BIT (1<<2)
286 #else
287 #define PWM_SERVO_2_OC_BIT 0
288 #endif
289 
290 //servo AUX3
291 #if USE_PWM3
292 #define PWM_SERVO_3 2 //#define PWM_SERVO_3_IDX 2
293 #define PWM_SERVO_3_TIMER TIM1
294 #define PWM_SERVO_3_GPIO GPIOE
295 #define PWM_SERVO_3_PIN GPIO11
296 #define PWM_SERVO_3_AF GPIO_AF1
297 #define PWM_SERVO_3_OC TIM_OC2
298 #define PWM_SERVO_3_OC_BIT (1<<1)
299 #else
300 #define PWM_SERVO_3_OC_BIT 0
301 #endif
302 
303 //servo AUX4
304 #if USE_PWM4
305 #define PWM_SERVO_4 3
306 #define PWM_SERVO_4_TIMER TIM1
307 #define PWM_SERVO_4_GPIO GPIOE
308 #define PWM_SERVO_4_PIN GPIO9
309 #define PWM_SERVO_4_AF GPIO_AF1
310 #define PWM_SERVO_4_OC TIM_OC1
311 #define PWM_SERVO_4_OC_BIT (1<<0)
312 #else
313 #define PWM_SERVO_4_OC_BIT 0
314 #endif
315 
316 //servo AUX5
317 #if USE_PWM5
318 #define PWM_SERVO_5 4
319 #define PWM_SERVO_5_TIMER TIM4
320 #define PWM_SERVO_5_GPIO GPIOD
321 #define PWM_SERVO_5_PIN GPIO13
322 #define PWM_SERVO_5_AF GPIO_AF2
323 #define PWM_SERVO_5_OC TIM_OC2
324 #define PWM_SERVO_5_OC_BIT (1<<1)
325 #else
326 #define PWM_SERVO_5_OC_BIT 0
327 #endif
328 
329 //servo AUX6
330 #if USE_PWM6
331 #define PWM_SERVO_6 5
332 #define PWM_SERVO_6_TIMER TIM4
333 #define PWM_SERVO_6_GPIO GPIOD
334 #define PWM_SERVO_6_PIN GPIO14
335 #define PWM_SERVO_6_AF GPIO_AF2
336 #define PWM_SERVO_6_OC TIM_OC3
337 #define PWM_SERVO_6_OC_BIT (1<<2)
338 #else
339 #define PWM_SERVO_6_OC_BIT 0
340 #endif
341 
342 //Buzzer (alarm)
343 #if USE_BUZZER
344 #define PWM_BUZZER
345 #define PWM_BUZZER_TIMER TIM2
346 #define PWM_BUZZER_GPIO GPIOA
347 #define PWM_BUZZER_PIN GPIO15
348 #define PWM_BUZZER_AF GPIO_AF1
349 #define PWM_BUZZER_OC TIM_OC1
350 #define PWM_BUZZER_OC_BIT (1<<0)
351 #define PWM_TIM2_CHAN_MASK (PWM_BUZZER_OC_BIT)
352 #else
353 #define PWM_BUZZER_OC_BIT 0
354 #endif
355 
356 #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)
357 #define PWM_TIM4_CHAN_MASK (PWM_SERVO_5_OC_BIT|PWM_SERVO_6_OC_BIT)
358 
359 #endif /* CONFIG_PX4FMU_2_4_H */