mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
hwdef: update HolybroG4_GPS
disable CAN2 (unused), and prevent sharing of DMA for GPS UART
This commit is contained in:
parent
f3e5e28364
commit
deab955a0f
@ -56,8 +56,8 @@ PB10 USART3_TX USART3
|
||||
PB11 USART3_RX USART3
|
||||
|
||||
# USART2, debug
|
||||
PA2 USART2_TX USART2
|
||||
PA3 USART2_RX USART2
|
||||
PA2 USART2_TX USART2 NODMA
|
||||
PA3 USART2_RX USART2 NODMA
|
||||
|
||||
# SWD debugging
|
||||
PA13 JTMS-SWDIO SWD
|
||||
@ -126,9 +126,9 @@ PA11 CAN1_RX CAN1
|
||||
PA12 CAN1_TX CAN1
|
||||
PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
|
||||
PB12 CAN2_RX CAN2
|
||||
PB13 CAN2_TX CAN2
|
||||
PB14 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
#PB12 CAN2_RX CAN2
|
||||
#PB13 CAN2_TX CAN2
|
||||
#PB14 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.HolybroG4_GPS"
|
||||
|
||||
@ -145,6 +145,8 @@ define GPS_MAX_RECEIVERS 1
|
||||
define GPS_MAX_INSTANCES 1
|
||||
define HAL_COMPASS_MAX_SENSORS 1
|
||||
|
||||
DMA_NOSHARE USART3*
|
||||
|
||||
# add support for moving baseline yaw
|
||||
define GPS_MOVING_BASELINE 1
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user