ardupilot/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Airspeed/hwdef.dat

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

14 lines
317 B
Plaintext
Raw Normal View History

include ../MatekL431/hwdef.inc
define HAL_USE_ADC FALSE
define STM32_ADC_USE_ADC1 FALSE
define HAL_DISABLE_ADC_DRIVER TRUE
# ------------------ I2C airspeed -------------------------
define HAL_PERIPH_ENABLE_AIRSPEED
# 10" DLVR sensor by default
define HAL_AIRSPEED_TYPE_DEFAULT 9
define AIRSPEED_MAX_SENSORS 1