mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 06:58:39 -04:00
HAL_ChibiOS: setup pwm counts, and cleanup mindpx-v2 PWM lines
This commit is contained in:
parent
1b9cebc3f2
commit
7c85d06600
@ -196,5 +196,6 @@ define HAL_BATT_CURR_SCALE 17.0
|
||||
define HAL_SERIAL5_PROTOCOL SerialProtocol_MAVLink
|
||||
define HAL_SERIAL5_BAUD 921600
|
||||
|
||||
|
||||
# 6 PWM available by default
|
||||
define BOARD_PWM_COUNT_DEFAULT 6
|
||||
|
||||
|
@ -44,8 +44,6 @@ UART_ORDER OTG1 UART4 USART2 USART3 UART8 USART1
|
||||
# UART4 is GPS
|
||||
PA0 UART4_TX UART4
|
||||
PA1 UART4_RX UART4
|
||||
PA2 TIM2_CH3 TIM2 PWM(15)
|
||||
PA3 TIM2_CH4 TIM2 PWM(16)
|
||||
PA4 VDD_5V_SENS ADC1 SCALE(2)
|
||||
|
||||
# SPI1 is fram bus
|
||||
@ -66,13 +64,30 @@ PA12 OTG_FS_DP OTG1
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
PA15 TIM2_CH1 TIM2 PWM(13) GPIO(54)
|
||||
|
||||
# PWM outputs
|
||||
PE9 TIM1_CH1 TIM1 PWM(1)
|
||||
PE11 TIM1_CH2 TIM1 PWM(2)
|
||||
PE13 TIM1_CH3 TIM1 PWM(3)
|
||||
PE14 TIM1_CH4 TIM1 PWM(4)
|
||||
|
||||
PD12 TIM4_CH1 TIM4 PWM(5)
|
||||
PD13 TIM4_CH2 TIM4 PWM(6)
|
||||
PD14 TIM4_CH3 TIM4 PWM(7)
|
||||
PD15 TIM4_CH4 TIM4 PWM(8)
|
||||
|
||||
PB4 TIM3_CH1 TIM3 PWM(9) GPIO(50)
|
||||
PC7 TIM3_CH2 TIM3 PWM(10) GPIO(51)
|
||||
PB0 TIM3_CH3 TIM3 PWM(11) GPIO(52)
|
||||
PB1 TIM3_CH4 TIM3 PWM(12) GPIO(53)
|
||||
PB2 GYRO_CS CS
|
||||
|
||||
PA15 TIM2_CH1 TIM2 PWM(13) GPIO(54)
|
||||
PB3 TIM2_CH2 TIM2 PWM(14) GPIO(55)
|
||||
PB4 TIM3_CH1 TIM3 PWM(9) GPIO(50)
|
||||
PA2 TIM2_CH3 TIM2 PWM(15)
|
||||
PA3 TIM2_CH4 TIM2 PWM(16)
|
||||
|
||||
PB2 GYRO_CS CS
|
||||
|
||||
PB5 SPI1_MOSI SPI1
|
||||
|
||||
# USART1 is SBUS
|
||||
@ -101,7 +116,6 @@ PC3 FMU_ADC1 ADC1
|
||||
PC4 FMU_ADC2 ADC1
|
||||
PC5 FMU_ADC3 ADC1
|
||||
PC6 TIM8_CH1 TIM8 RCIN PULLDOWN LOW # also USART6_RX for serial RC
|
||||
PC7 TIM3_CH2 TIM3 PWM(10) GPIO(51)
|
||||
|
||||
PC8 SDIO_D0 SDIO
|
||||
PC9 SDIO_D1 SDIO
|
||||
@ -130,10 +144,6 @@ PD9 USART3_RX USART3
|
||||
PD10 NRF_INT INPUT
|
||||
PD11 ACCEL_MAG_CS CS
|
||||
|
||||
PD12 TIM4_CH1 TIM4 PWM(5)
|
||||
PD13 TIM4_CH2 TIM4 PWM(6)
|
||||
PD14 TIM4_CH3 TIM4 PWM(7)
|
||||
PD15 TIM4_CH4 TIM4 PWM(8)
|
||||
|
||||
# UART8 is FrSky
|
||||
PE0 UART8_RX UART8
|
||||
@ -150,12 +160,8 @@ PE6 SPI4_MOSI SPI4
|
||||
PE7 UART7_RX UART7
|
||||
PE8 UART7_TX UART7
|
||||
|
||||
PE9 TIM1_CH1 TIM1 PWM(1)
|
||||
PE10 MPU_DRDY INPUT
|
||||
PE11 TIM1_CH2 TIM1 PWM(2)
|
||||
PE12 FRAM_CS CS
|
||||
PE13 TIM1_CH3 TIM1 PWM(3)
|
||||
PE14 TIM1_CH4 TIM1 PWM(4)
|
||||
PE15 NRF_CS CS
|
||||
|
||||
# SPI device table
|
||||
@ -189,3 +195,6 @@ define HAL_BATT_VOLT_PIN 12
|
||||
define HAL_BATT_CURR_PIN 10
|
||||
define HAL_BATT_VOLT_SCALE 10.1
|
||||
define HAL_BATT_CURR_SCALE 17.0
|
||||
|
||||
# 12 PWM available by default
|
||||
define BOARD_PWM_COUNT_DEFAULT 12
|
||||
|
@ -133,3 +133,6 @@ define HAL_BARO_MS5611_I2C_ADDR 0x77
|
||||
SPIDEV mpu6000 SPI1 DEVID1 MPU_CS MODE3 1*MHZ 8*MHZ
|
||||
SPIDEV dataflash SPI3 DEVID1 FLASH_CS MODE3 1*MHZ 8*MHZ
|
||||
|
||||
# 8 PWM available by default
|
||||
define BOARD_PWM_COUNT_DEFAULT 8
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user