HAL_ChibiOS: fixed crazyflie motor order

This commit is contained in:
Andrew Tridgell 2018-02-15 15:37:34 +11:00
parent cf00bd99ea
commit d5fc1ff3d4

View File

@ -46,10 +46,10 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
PA1 TIM2_CH2 TIM2 PWM(1) # MOTOR1
PB11 TIM2_CH4 TIM2 PWM(2) # MOTOR2
PA15 TIM2_CH1 TIM2 PWM(3) # MOTOR3
PB9 TIM4_CH4 TIM4 PWM(4) # MOTOR4
PA1 TIM2_CH2 TIM2 PWM(1) # front-right
PB11 TIM2_CH4 TIM2 PWM(4) # rear-right
PA15 TIM2_CH1 TIM2 PWM(2) # rear-left
PB9 TIM4_CH4 TIM4 PWM(3) # front-left
PC13 MPU_INT INPUT
PC14 MPU_FSYNC OUTPUT LOW
@ -91,6 +91,9 @@ PC11 USART3_RX USART3 # E_RX1
# setup I2C order
I2C_ORDER I2C3 I2C1
# we need I2C clock at 400kHz for IMU
define HAL_I2C_MAX_CLOCK 400000
# order of UARTs (and USB)
UART_ORDER OTG1 USART2 USART3