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

16 lines
378 B
Plaintext

include ../MatekL431/hwdef.inc
define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Airspeed"
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