mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: fixed GPIO lines for QioTekZealotF427
This commit is contained in:
parent
f232fc551b
commit
aa8ebc403e
|
@ -159,10 +159,10 @@ PD14 TIM4_CH3 TIM4 PWM(12) GPIO(61)
|
||||||
PC9 TIM3_CH4 TIM3 PWM(13) GPIO(62) NODMA
|
PC9 TIM3_CH4 TIM3 PWM(13) GPIO(62) NODMA
|
||||||
PC8 TIM3_CH3 TIM3 PWM(14) GPIO(63) NODMA
|
PC8 TIM3_CH3 TIM3 PWM(14) GPIO(63) NODMA
|
||||||
|
|
||||||
PC14 EXTERN_GPIO1 GPIO(1)
|
PC14 EXTERN_GPIO1 OUTPUT GPIO(1)
|
||||||
PC13 EXTERN_GPIO2 GPIO(2)
|
PC13 EXTERN_GPIO2 OUTPUT GPIO(2)
|
||||||
PE4 EXTERN_GPIO3 GPIO(3)
|
PE4 EXTERN_GPIO3 OUTPUT GPIO(3)
|
||||||
PE6 EXTERN_GPIO4 GPIO(4)
|
PE6 EXTERN_GPIO4 OUTPUT GPIO(4)
|
||||||
define RELAY1_PIN_DEFAULT 1
|
define RELAY1_PIN_DEFAULT 1
|
||||||
define RELAY2_PIN_DEFAULT 2
|
define RELAY2_PIN_DEFAULT 2
|
||||||
define RELAY3_PIN_DEFAULT 3
|
define RELAY3_PIN_DEFAULT 3
|
||||||
|
|
Loading…
Reference in New Issue