mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: update truenav hwdef
This commit is contained in:
parent
1ec61c57ba
commit
873e2eac7d
|
@ -30,8 +30,6 @@ PA12 CAN1_TX CAN1
|
|||
PB1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
PB6 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW HIGH
|
||||
|
||||
CAN_ORDER 1
|
||||
|
||||
# make bl baudrate match debug baudrate for easier debugging
|
||||
define BOOTLOADER_BAUDRATE 57600
|
||||
|
||||
|
|
|
@ -68,24 +68,22 @@ PB11 I2C2_SDA I2C2
|
|||
|
||||
define HAL_I2C_CLEAR_ON_TIMEOUT 0
|
||||
define HAL_I2C_INTERNAL_MASK 1
|
||||
COMPASS QMC5883L I2C:0:0xd false ROTATION_PITCH_180_YAW_90
|
||||
COMPASS QMC5883L I2C:0:0xd false ROTATION_YAW_180
|
||||
|
||||
# ---------------------- CAN bus -------------------------
|
||||
CAN_ORDER 1
|
||||
|
||||
PA11 CAN1_RX CAN1
|
||||
PA12 CAN1_TX CAN1
|
||||
PB1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
PB6 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
|
||||
define HAL_CAN_POOL_SIZE 12000
|
||||
define HAL_CAN_POOL_SIZE 8000
|
||||
|
||||
# ---------------------- UARTs ---------------------------
|
||||
SERIAL_ORDER EMPTY USART1
|
||||
|
||||
# USART1 for GPS
|
||||
PA9 USART1_TX USART1 SPEED_HIGH
|
||||
PA10 USART1_RX USART1 SPEED_HIGH
|
||||
PA10 USART1_RX USART1 SPEED_HIGH
|
||||
|
||||
# keep ROMFS uncompressed as we don't have enough RAM
|
||||
# to uncompress the bootloader at runtime
|
||||
|
@ -105,10 +103,10 @@ define BARO_MAX_INSTANCES 1
|
|||
define HAL_PERIPH_GPS_PORT_DEFAULT 1
|
||||
|
||||
# GPS PPS
|
||||
# PA15 GPS_PPS_IN INPUT FLOATING
|
||||
PA15 GPS_PPS_IN INPUT
|
||||
|
||||
# PWM, WS2812 LED
|
||||
# PB10 TIM2_CH3 TIM2 PWM(1)
|
||||
PB10 TIM2_CH3 TIM2 PWM(1)
|
||||
|
||||
define CAN_APP_NODE_NAME "in.sierraaerospace.TrueNavIC"
|
||||
|
||||
|
|
|
@ -42,6 +42,7 @@ define HAL_USE_SERIAL FALSE
|
|||
PA11 CAN1_RX CAN1
|
||||
PA12 CAN1_TX CAN1
|
||||
PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
PA2 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
|
||||
# make bl baudrate match debug baudrate for easier debugging
|
||||
define BOOTLOADER_BAUDRATE 57600
|
||||
|
|
|
@ -29,8 +29,8 @@ FLASH_SIZE_KB 256
|
|||
SERIAL_ORDER EMPTY USART2
|
||||
|
||||
# USART2, GPS
|
||||
PB3 USART2_TX USART2
|
||||
PB4 USART2_RX USART2
|
||||
PB3 USART2_TX USART2 SPEED HIGH
|
||||
PB4 USART2_RX USART2 SPEED HIGH
|
||||
|
||||
# USART1, debug, disabled to save flash
|
||||
# PB6 USART1_TX USART1
|
||||
|
@ -109,3 +109,5 @@ env ROMFS_UNCOMPRESSED True
|
|||
PA3 TIM2_CH4 TIM2 PWM(1)
|
||||
|
||||
DMA_NOSHARE USART2*
|
||||
|
||||
define CAN_APP_NODE_NAME "in.sierraaerospace.TrueNavPro-G4"
|
||||
|
|
Loading…
Reference in New Issue