ardupilot/libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef.dat

20 lines
458 B
Plaintext
Raw Normal View History

include ../f103-periph/hwdef.inc
2019-10-19 01:36:33 -03:00
define HAL_AIRSPEED_BUS_DEFAULT 0
define AIRSPEED_MAX_SENSORS 1
define HAL_PERIPH_ENABLE_RANGEFINDER
define AP_PERIPH_RANGEFINDER_PORT_DEFAULT 3
# we're too low on flash with old compiler for bootloader
define HAL_NO_ROMFS_SUPPORT
include ../include/no_bootloader_DFU.inc
# setup for MSP
define HAL_MSP_ENABLED 1
# some lidars take a long time to init, keep probing till we find it
define AP_PERIPH_PROBE_CONTINUOUS 1