mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-31 04:58:30 -04:00
AP_HAL_ChibiOS: add hwdef MFE_AirSpeed_CAN
This commit is contained in:
parent
6efe210549
commit
b051f4d557
@ -0,0 +1,6 @@
|
||||
include ../f103-periph/hwdef-bl.inc
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 6103
|
||||
undef PA4
|
||||
PA10 LED_BOOTLOADER OUTPUT LOW
|
25
libraries/AP_HAL_ChibiOS/hwdef/MFE_AirSpeed_CAN/hwdef.dat
Normal file
25
libraries/AP_HAL_ChibiOS/hwdef/MFE_AirSpeed_CAN/hwdef.dat
Normal file
@ -0,0 +1,25 @@
|
||||
include ../f103-periph/hwdef.inc
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 6103
|
||||
|
||||
undef PA4
|
||||
undef PA9
|
||||
undef PA10
|
||||
# a LED to flash
|
||||
PA10 LED OUTPUT LOW
|
||||
|
||||
# order of UARTs
|
||||
SERIAL_ORDER EMPTY EMPTY EMPTY USART2
|
||||
|
||||
# USART2 for debug (disabled)
|
||||
PA2 USART2_TX USART2 SPEED_HIGH NODMA
|
||||
PA3 USART2_RX USART2 SPEED_HIGH NODMA
|
||||
|
||||
define HAL_AIRSPEED_BUS_DEFAULT 0
|
||||
|
||||
# 10" DLVR sensor by default
|
||||
define HAL_AIRSPEED_TYPE_DEFAULT 1
|
||||
define AIRSPEED_MAX_SENSORS 1
|
||||
|
||||
define HAL_PERIPH_ENABLE_AIRSPEED
|
Loading…
Reference in New Issue
Block a user