Paparazzi UAS  v5.18.0_stable
Paparazzi is a free software Unmanned Aircraft System.
px4fmu_4.0.h
Go to the documentation of this file.
1 #ifndef CONFIG_PX4FMU_4_0_H
2 #define CONFIG_PX4FMU_4_0_H
3 
4 #define BOARD_PX4FMU_V4
5 
6 /* differences between board not implemented ATM consider them all the same for time being */
7 //#define BOARD_PX4FMU_V4_R12
8 //#define BOARD_PX4FMU_V4_R14
9 //#define BOARD_PX4FMU_V4_R15
10 
11 /* PX4FMU_V4 a.k.a. Pixracer board has a 24MHz external clock and 168MHz internal. */
12 
13 /* STM32F4 STM32F427VIT6 */
14 #define EXT_CLK 24000000
15 #define AHB_CLK 168000000
16 
17 //#define STM32F4 //to debug ADC on F4 does no work
18 //#define ADC_SAMPLE_TIME ADC_SMPR_SMP_56CYC //to debug ADC on F4 does no work
19 
20 /* On PCB there is a Multicolor LED */
21 
22 /* Red */
23 #ifndef USE_LED_1
24 #define USE_LED_1 1
25 #endif
26 #define LED_1_GPIO GPIOB
27 #define LED_1_GPIO_PIN GPIO11
28 #define LED_1_GPIO_ON gpio_clear
29 #define LED_1_GPIO_OFF gpio_set
30 #define LED_1_AFIO_REMAP ((void)0)
31 
32 /* Green */
33 #ifndef USE_LED_2
34 #define USE_LED_2 1
35 #endif
36 #define LED_2_GPIO GPIOB
37 #define LED_2_GPIO_PIN GPIO1
38 #define LED_2_GPIO_ON gpio_clear
39 #define LED_2_GPIO_OFF gpio_set
40 #define LED_2_AFIO_REMAP ((void)0)
41 
42 /* Blue */
43 #ifndef USE_LED_3
44 #define USE_LED_3 1
45 #endif
46 #define LED_3_GPIO GPIOB
47 #define LED_3_GPIO_PIN GPIO3
48 #define LED_3_GPIO_ON gpio_clear
49 #define LED_3_GPIO_OFF gpio_set
50 #define LED_3_AFIO_REMAP ((void)0)
51 
52 /* On PCB other LEDs */
53 /* The Green Pixracer Power LED in not controllable, not on a MCU pin */
54 
55 /* UART */
56 
57 /* -WiFi ESP Connector, it is just a serial port*/
58 //TODO: Test
59 #define UART1_GPIO_AF GPIO_AF7
60 #define UART1_GPIO_PORT_RX GPIOB
61 #define UART1_GPIO_RX GPIO7
62 #define UART1_GPIO_PORT_TX GPIOB
63 #define UART1_GPIO_TX GPIO6
64 
65 //Not used yet unil find some time to test
66 /*
67 #define ESP8266_TX
68 #define ESP8266_RX
69 #define ESP8266_PD ( power down )
70 #define ESP8266_GPIO2
71 #define ESP8266_RESET
72 #define ESP8266_GPIO0
73 #define ESP8266_RTS
74 #define ESP8266_CTS
75 */
76 
77 /* -TELEM1 Connector */
78 #define UART2_GPIO_AF GPIO_AF7
79 #define UART2_GPIO_PORT_RX GPIOD
80 #define UART2_GPIO_RX GPIO6
81 #define UART2_GPIO_PORT_TX GPIOD
82 #define UART2_GPIO_TX GPIO5
83 #define UART2_GPIO_PORT_CTS GPIOD
84 #define UART2_GPIO_CTS GPIO3
85 #define UART2_GPIO_PORT_RTS GPIOD
86 #define UART2_GPIO_RTS GPIO4
87 
88 /* -TELEM2 Connector */
89 #define UART3_GPIO_AF GPIO_AF7
90 #define UART3_GPIO_PORT_RX GPIOD
91 #define UART3_GPIO_RX GPIO9
92 #define UART3_GPIO_PORT_TX GPIOD
93 #define UART3_GPIO_TX GPIO8
94 #define UART3_GPIO_PORT_CTS GPIOD
95 #define UART3_GPIO_CTS GPIO11
96 #define UART3_GPIO_PORT_RTS GPIOD
97 #define UART3_GPIO_RTS GPIO12
98 
99 /* -GPS Connector */
100 #define UART4_GPIO_AF GPIO_AF8
101 #define UART4_GPIO_PORT_RX GPIOA
102 #define UART4_GPIO_RX GPIO1
103 #define UART4_GPIO_PORT_TX GPIOA
104 #define UART4_GPIO_TX GPIO0
105 
106 /* e.g. for a Spektrum satellite receiver rx only)*/
107 #define UART6_GPIO_AF GPIO_AF8
108 #define UART6_GPIO_PORT_RX GPIOC
109 #define UART6_GPIO_RX GPIO7
110 
111 /* Serial Debugging Info Connector, not used with PPRZ as of now, use JTAG for debugging, so this uart can be put to other use if really needed */
112 #define UART7_GPIO_AF GPIO_AF8
113 #define UART7_GPIO_PORT_RX GPIOE
114 #define UART7_GPIO_RX GPIO7
115 #define UART7_GPIO_PORT_TX GPIOE
116 #define UART7_GPIO_TX GPIO8
117 
118 /* Connector -FRS FrSky */
119 #define UART8_GPIO_AF GPIO_AF8
120 #define UART8_GPIO_PORT_RX GPIOE
121 #define UART8_GPIO_RX GPIO0
122 #define UART8_GPIO_PORT_TX GPIOE
123 #define UART8_GPIO_TX GPIO1
124 
125 /* Soft binding Spektrum */
126 //TODO: Test and or FIXME:
127 #define RADIO_CONTROL_POWER_PORT GPIOE
128 #define RADIO_CONTROL_POWER_PIN GPIO4 //SPEKTRUM POWER
129 #define RADIO_CONTROL_POWER_ON gpio_clear // yes, inverted
130 #define RADIO_CONTROL_POWER_OFF gpio_set
131 
132 //A receiver on powered on 3.3v
133 #define PERIPHERAL3V3_ENABLE_PORT GPIOC //VDD_3V3_PERIPHERAL_EN
134 #define PERIPHERAL3V3_ENABLE_PIN GPIO5
135 #define PERIPHERAL3V3_ENABLE_ON gpio_set
136 #define PERIPHERAL3V3_ENABLE_OFF gpio_clear
137 
138 /* Turn SBUS invert */
139 //TODO: Test
140 #define RC_POLARITY_GPIO_PORT GPIOC
141 #define RC_POLARITY_GPIO_PIN GPIO13
142 
143 #define SPEKTRUM_UART6_RCC RCC_USART6
144 #define SPEKTRUM_UART6_BANK GPIOC
145 #define SPEKTRUM_UART6_PIN GPIO7
146 #define SPEKTRUM_UART6_AF GPIO_AF8
147 #define SPEKTRUM_UART6_IRQ NVIC_USART6_IRQ
148 #define SPEKTRUM_UART6_ISR usart6_isr
149 #define SPEKTRUM_UART6_DEV USART6
150 
151 /* SPI */
152 
153 /* SPI1 for MPU and extra accel/gyro/mag */
154 #define SPI1_GPIO_AF GPIO_AF5
155 #define SPI1_GPIO_PORT_MISO GPIOA
156 #define SPI1_GPIO_MISO GPIO6
157 #define SPI1_GPIO_PORT_MOSI GPIOA
158 #define SPI1_GPIO_MOSI GPIO7
159 #define SPI1_GPIO_PORT_SCK GPIOA
160 #define SPI1_GPIO_SCK GPIO5
161 
162 /* SPI2 for FRAM, connects to BARO */
163 #define SPI2_GPIO_AF GPIO_AF5
164 #define SPI2_GPIO_PORT_MISO GPIOB
165 #define SPI2_GPIO_MISO GPIO14
166 #define SPI2_GPIO_PORT_MOSI GPIOB
167 #define SPI2_GPIO_MOSI GPIO15
168 #define SPI2_GPIO_PORT_SCK GPIOB
169 #define SPI2_GPIO_SCK GPIO10
170 
171 /*
172  * SPI slave pin declaration
173  */
174 
175 /* note :
176 Active-Low Push-Pull Data-Ready Output. DRDY goes low when a new conversion result is available in the data register.
177 When a read-operation of an RTD resistance data register occurs, DRDY returns high.
178 */
179 /*
180  * SPI slave pin declaration
181  */
182 
183 //So use best spec'd sensors as second or ref the other or determine it on task type?
184 /* EXTRA ACC_GYRO_CS on SPI1 ICM 20609-G*/
185 // TODO: Make it useful
186 #define SPI_SELECT_SLAVE0_PORT GPIOC
187 #define SPI_SELECT_SLAVE0_PIN GPIO15
188 
189 /* EXTRA_MAG_CS on SPI1 HMC5983*/
190 //See https://docs.google.com/spreadsheets/d/1gVlKZBvRNTXldoxTXwipGaaHmtF9DNPaftDrzKA47mM/edit#gid=0
191 #define SPI_SELECT_SLAVE1_PORT GPIOE
192 #define SPI_SELECT_SLAVE1_PIN GPIO15
193 
194 /* MDL */
195 // FIXME: Test n fix or emoveal
196 //#define SPI_SELECT_SLAVE1_PORT GPIOE
197 //#define SPI_SELECT_SLAVE1_PIN GPIO15
198 
199 /* MPU_9250_CS on SPI1 */
200 #define SPI_SELECT_SLAVE2_PORT GPIOC
201 #define SPI_SELECT_SLAVE2_PIN GPIO2
202 
203 /* MS5611 BARO_CS on SPI2 - FRAM*/
204 #define SPI_SELECT_SLAVE3_PORT GPIOD
205 #define SPI_SELECT_SLAVE3_PIN GPIO7
206 
207 /* FRAM on SPI2 */
208 #define SPI_SELECT_SLAVE4_PORT GPIOD
209 #define SPI_SELECT_SLAVE4_PIN GPIO10
210 
211 /* SPI3 NSS on microSD connector */
212 //FIXME: not tested
213 //#define SPI_SELECT_SLAVE5_PORT GPIOA
214 //#define SPI_SELECT_SLAVE5_PIN GPIO4
215 
216 /* SDIO to microSD card connector */
217 #define SDIO_AF GPIO_AF12
218 #define SDIO_D0_PORT GPIOC
219 #define SDIO_D0_PIN GPIO8
220 #define SDIO_D1_PORT GPIOC
221 #define SDIO_D1_PIN GPIO9
222 #define SDIO_D2_PORT GPIOC
223 #define SDIO_D2_PIN GPIO10
224 #define SDIO_D3_PORT GPIOC
225 #define SDIO_D3_PIN GPIO11
226 #define SDIO_CK_PORT GPIOC
227 #define SDIO_CK_PIN GPIO12
228 #define SDIO_CMD_PORT GPIOD
229 #define SDIO_CMD_PIN GPIO2
230 
231 /* Onboard ADCs */
232 #if USE_AD_TIM2
233 #undef USE_AD_TIM2 // timer2 is used by the buzzer
234 #endif
235 #define USE_AD_TIM3 1
236 
237 // Internal ADC used for board voltage level measurement
238 #ifndef USE_ADC_1
239 #define USE_ADC_1 1
240 #endif
241 #if USE_ADC_1
242 #define AD1_1_CHANNEL 4 //ADC12_IN4
243 #define ADC_1 AD1_1
244 #define ADC_1_GPIO_PORT GPIOA
245 #define ADC_1_GPIO_PIN GPIO4
246 #endif
247 
248 #ifndef USE_ADC_2
249 #define USE_ADC_2 1
250 #endif
251 #if USE_ADC_2
252 #define AD1_2_CHANNEL 2 // ADC123_IN2 (--> IN2 corresponds to channel 2)
253 #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.
254 #define ADC_2_GPIO_PORT GPIOA
255 #define ADC_2_GPIO_PIN GPIO2
256 #endif
257 
258 #ifndef USE_ADC_3
259 #define USE_ADC_3 1
260 #endif
261 #if USE_ADC_3
262 #define AD1_3_CHANNEL 3 // ADC123_IN3
263 #define ADC_3 AD1_3
264 #define ADC_3_GPIO_PORT GPIOA
265 #define ADC_3_GPIO_PIN GPIO3
266 #endif
267 
268 //ADC_pin_RSSI_IN
269 #ifndef USE_ADC_4
270 #define USE_ADC_4 1
271 #endif
272 #if USE_ADC_4
273 #define AD1_4_CHANNEL 11 // ADC123_IN11
274 #define ADC_4 AD1_4
275 #define ADC_4_GPIO_PORT GPIOC
276 #define ADC_4_GPIO_PIN GPIO1
277 #endif
278 
279 /* Allow to define another ADC_CHANNEL_VSUPPLY in the airframe file */
280 #ifndef ADC_CHANNEL_VSUPPLY
281  #define ADC_CHANNEL_VSUPPLY ADC_1 // Per default for the board to sense voltage (V) level via external sensor is via ADC_2
282  #define DefaultVoltageOfAdc(adc) (10.5 * (float)adc) // FIXME: More precise value scale internal vdd to 5V
283 #else
284  #if USE_ADC_2
285  #define DefaultVoltageOfAdc(adc) ((3.3f/4096.0f) * 10.245f * (float)adc) // About the value scale for a common 3DR clone Power Brick
286  #else
287  #define DefaultVoltageOfAdc(adc) ((3.3f/4096.0f) * 6.0f * (float)adc) // About the value scale for a common other sensor
288  #endif
289 #endif
290 
291 /* Allow to define another ADC for Current measurement in the airframe file */
292 #ifndef ADC_CHANNEL_CURRENT
293 #define ADC_CHANNEL_CURRENT ADC_3 // Per default for the board to sense current (I) via external sensor is via ADC_3
294 #endif
295 
296 #if USE_ADC_3
297 #define DefaultMilliAmpereOfAdc(adc) (9.55 * ((float)adc))// Quite close to the value scale for a common 3DR clone Power Brick
298 #else
299 #define DefaultMilliAmpereOfAdc(adc) (0.1 * ((float)adc)) // FIXME: Value scale internal current use, for whatever it is useful
300 #endif
301 
302 #ifndef ADC_CHANNEL_RSSI
303 #define ADC_CHANNEL_RSSI ADC_4
304 #endif
305 
306 /* I2C mapping */
307 #define I2C1_GPIO_PORT GPIOB
308 #define I2C1_GPIO_SCL GPIO8
309 #define I2C1_GPIO_SDA GPIO9
310 
311 //Enable Onboard Barometer per default
312 #ifndef USE_BARO_BOARD
313 #define USE_BARO_BOARD 1
314 #endif
315 
316 /* Another Magnetometer on board on R14 a HMC5983 on R15 ST ,so not the one in the IMU 9250*/
317 //FIXME: better default option for use of maybe fuse data
318 #ifndef USE_MAGNETOMETER_B
319 #define USE_MAGNETOMETER_B 0
320 #endif
321 
322 /* Default actuators driver */
323 #define DEFAULT_ACTUATORS "subsystems/actuators/actuators_pwm.h"
324 #define ActuatorDefaultSet(_x,_y) ActuatorPwmSet(_x,_y)
325 #define ActuatorsDefaultInit() ActuatorsPwmInit()
326 #define ActuatorsDefaultCommit() ActuatorsPwmCommit()
327 
328 /* PWM */
329 #define PWM_USE_TIM1 1
330 #define PWM_USE_TIM4 1
331 
332 //TODO: ifdef USE_SERVO6 for PPM out to e.g. servo extender board ...
333 // Basically a inter mcu Extra device ;)
334 
335 #define USE_PWM1 1
336 #define USE_PWM2 1
337 #define USE_PWM3 1
338 #define USE_PWM4 1
339 #define USE_PWM5 1
340 #define USE_PWM6 1
341 
342 /* Servo 1 */
343 #if USE_PWM1
344 #define PWM_SERVO_1 0
345 #define PWM_SERVO_1_TIMER TIM1
346 #define PWM_SERVO_1_GPIO GPIOE
347 #define PWM_SERVO_1_PIN GPIO14
348 #define PWM_SERVO_1_AF GPIO_AF1
349 #define PWM_SERVO_1_OC TIM_OC4
350 #define PWM_SERVO_1_OC_BIT (1<<3)
351 #else
352 #define PWM_SERVO_1_OC_BIT 0
353 #endif
354 
355 /* Servo 2 */
356 #if USE_PWM2
357 #define PWM_SERVO_2 1
358 #define PWM_SERVO_2_TIMER TIM1
359 #define PWM_SERVO_2_GPIO GPIOE
360 #define PWM_SERVO_2_PIN GPIO13
361 #define PWM_SERVO_2_AF GPIO_AF1
362 #define PWM_SERVO_2_OC TIM_OC3
363 #define PWM_SERVO_2_OC_BIT (1<<2)
364 #else
365 #define PWM_SERVO_2_OC_BIT 0
366 #endif
367 
368 /* Servo 3 */
369 #if USE_PWM3
370 #define PWM_SERVO_3 2 //#define PWM_SERVO_3_IDX 2
371 #define PWM_SERVO_3_TIMER TIM1
372 #define PWM_SERVO_3_GPIO GPIOE
373 #define PWM_SERVO_3_PIN GPIO11
374 #define PWM_SERVO_3_AF GPIO_AF1
375 #define PWM_SERVO_3_OC TIM_OC2
376 #define PWM_SERVO_3_OC_BIT (1<<1)
377 #else
378 #define PWM_SERVO_3_OC_BIT 0
379 #endif
380 
381 /* Servo 4 */
382 #if USE_PWM4
383 #define PWM_SERVO_4 3
384 #define PWM_SERVO_4_TIMER TIM1
385 #define PWM_SERVO_4_GPIO GPIOE
386 #define PWM_SERVO_4_PIN GPIO9
387 #define PWM_SERVO_4_AF GPIO_AF1
388 #define PWM_SERVO_4_OC TIM_OC1
389 #define PWM_SERVO_4_OC_BIT (1<<0)
390 #else
391 #define PWM_SERVO_4_OC_BIT 0
392 #endif
393 
394 /* Servo 5 */
395 #if USE_PWM5
396 #define PWM_SERVO_5 4
397 #define PWM_SERVO_5_TIMER TIM4
398 #define PWM_SERVO_5_GPIO GPIOD
399 #define PWM_SERVO_5_PIN GPIO13
400 #define PWM_SERVO_5_AF GPIO_AF2
401 #define PWM_SERVO_5_OC TIM_OC2
402 #define PWM_SERVO_5_OC_BIT (1<<1)
403 #else
404 #define PWM_SERVO_5_OC_BIT 0
405 #endif
406 
407 /* Servo 6 */
408 #if USE_PWM6
409 #define PWM_SERVO_6 5
410 #define PWM_SERVO_6_TIMER TIM4
411 #define PWM_SERVO_6_GPIO GPIOD
412 #define PWM_SERVO_6_PIN GPIO14
413 #define PWM_SERVO_6_AF GPIO_AF2
414 #define PWM_SERVO_6_OC TIM_OC3
415 #define PWM_SERVO_6_OC_BIT (1<<2)
416 #else
417 #define PWM_SERVO_6_OC_BIT 0
418 #endif
419 
420 #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)
421 #define PWM_TIM4_CHAN_MASK (PWM_SERVO_5_OC_BIT|PWM_SERVO_6_OC_BIT)
422 
423 /*
424  * PWM input, also could be used for
425  */
426 // PWM_INPUT1 on TIM4
427 #ifdef USE_PWM_INPUT1
428 #define PWM_INPUT1_GPIO_PORT GPIOD
429 #define PWM_INPUT1_GPIO_PIN GPIO12
430 #define PWM_INPUT1_GPIO_AF GPIO_AF2
431 
432 #define PWM_INPUT1_TIMER TIM4
433 #define PWM_INPUT1_CHANNEL_PERIOD TIM_IC1
434 #define PWM_INPUT1_CHANNEL_DUTY TIM_IC2
435 #define PWM_INPUT1_TIMER_INPUT TIM_IC_IN_TI1
436 #define PWM_INPUT1_SLAVE_TRIG TIM_SMCR_TS_TI1FP1
437 #define PWM_INPUT1_IRQ NVIC_TIM4_IRQ
438 #define PWM_INPUT1_CC_IE (TIM_DIER_CC1IE | TIM_DIER_CC2IE)
439 #define USE_PWM_INPUT_TIM4 TRUE
440 
441 #ifdef PWM_INPUT1_TICKS_PER_USEC
442 #define TIM4_TICKS_PER_USEC PWM_INPUT1_TICKS_PER_USEC
443 #endif
444 #define TIM4_PWM_INPUT_IDX 0
445 #define TIM4_CC_IF_PERIOD TIM_SR_CC1IF
446 #define TIM4_CC_IF_DUTY TIM_SR_CC2IF
447 #define TIM4_CCR_PERIOD TIM4_CCR1
448 #define TIM4_CCR_DUTY TIM4_CCR2
449 #endif
450 
451 // PWM_INPUT2 on TIM?
452 //FIXME: Find some useful not often used pin to outside world...
453 
454 /* Ofboard LED Safety LED */
455 #ifndef USE_LED_4
456 #define USE_LED_4 1
457 #endif
458 #define LED_4_GPIO GPIOC
459 #define LED_4_GPIO_PIN GPIO3
460 #define LED_4_GPIO_ON gpio_clear
461 #define LED_4_GPIO_OFF gpio_set
462 #define LED_4_AFIO_REMAP ((void)0)
463 
464 //#if USE_LED_4
465 //#ifndef SAFETY_WARNING_LED
466 #define SAFETY_WARNING_LED 4
467 //#endif
468 //#endif
469 // #define LED_SAFETY_GPIO_PORT LED_4_GPIO
470 // #define LED_SAFETY_GPIO_PIN LED_4_GPIO_PIN
471 // #define LED_SAFETY_GPIO_ON LED_4_GPIO_ON
472 // #define LED_SAFETY_GPIO_OFF LED_4_GPIO_OFF
473 // #define LED_SAFETY_AFIO_REMAP LED_4_AFIO_REMAP
474 
475 /* Safety Button */
476 #define BUTTON_SAFETY_GPIO_PORT GPIOC
477 #define BUTTON_SAFETY_GPIO_PIN GPIO4
478 
479 /* Buzzer (A.k.a. Alarm) */
480 #if USE_BUZZER
481 #define PWM_BUZZER
482 #define PWM_BUZZER_TIMER TIM2
483 #define PWM_BUZZER_GPIO GPIOA
484 #define PWM_BUZZER_PIN GPIO15
485 #define PWM_BUZZER_AF GPIO_AF1
486 #define PWM_BUZZER_OC TIM_OC1
487 #define PWM_BUZZER_OC_BIT (1<<0)
488 #define PWM_TIM2_CHAN_MASK (PWM_BUZZER_OC_BIT)
489 #else
490 #define PWM_BUZZER_OC_BIT 0
491 #endif
492 
493 #endif /* CONFIG_PX4FMU_4_0_H */