mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: update f303-MatekGPS to allow disable of MSP
and use DMA for MSP
This commit is contained in:
parent
37506c2f3a
commit
e260c7ad59
|
@ -22,7 +22,7 @@ define HAL_WATCHDOG_ENABLED_DEFAULT true
|
|||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
define CH_CFG_ST_FREQUENCY 100000
|
||||
define CH_CFG_ST_FREQUENCY 1000
|
||||
define CH_CFG_ST_TIMEDELTA 0
|
||||
|
||||
# assume the 256k flash part for now
|
||||
|
@ -83,7 +83,6 @@ define IO_THD_WA_SIZE 512
|
|||
|
||||
define HAL_NO_GCS
|
||||
define HAL_NO_LOGGING
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define HAL_MINIMIZE_FEATURES 0
|
||||
|
||||
|
@ -127,8 +126,8 @@ PA2 USART2_TX USART2 SPEED_HIGH NODMA
|
|||
PA3 USART2_RX USART2 SPEED_HIGH NODMA
|
||||
|
||||
# USART3, for MSP
|
||||
PB10 USART3_TX USART3 SPEED_HIGH NODMA
|
||||
PB11 USART3_RX USART3 SPEED_HIGH NODMA
|
||||
PB10 USART3_TX USART3 SPEED_HIGH
|
||||
PB11 USART3_RX USART3 SPEED_HIGH
|
||||
|
||||
# use a default node ID so this works with MSP only
|
||||
define HAL_CAN_DEFAULT_NODE_ID 112
|
||||
|
@ -150,11 +149,12 @@ define HAL_PERIPH_ENABLE_AIRSPEED
|
|||
define HAL_PERIPH_ENABLE_RANGEFINDER
|
||||
define HAL_PERIPH_ENABLE_MSP
|
||||
|
||||
# allow for rangefinder to be plugged in on "MSP" port
|
||||
define HAL_PERIPH_ADSB_PORT_DEFAULT 1
|
||||
define HAL_PERIPH_ENABLE_ADSB
|
||||
|
||||
# setup for MSP
|
||||
define HAL_MSP_ENABLED 1
|
||||
define AP_PERIPH_MSP_PORT_DEFAULT 2
|
||||
|
||||
# disable rangefinder by default
|
||||
define AP_PERIPH_RANGEFINDER_PORT_DEFAULT -1
|
||||
|
||||
# the M8 GPS is good at 10Hz, but the M9 is better at 5Hz,
|
||||
# so stick to 5Hz as the firmware is shared
|
||||
|
|
Loading…
Reference in New Issue