From 90e488d29d8ad54ccd64b60c87454f4f4bc50b33 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 9 Sep 2020 12:04:42 +1000 Subject: [PATCH] HAL_ChibiOS: set airspeed type in f303-MatekGPS fw --- libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat index d4bcc27046..994aa99861 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat @@ -159,3 +159,7 @@ define HAL_MSP_ENABLED 1 # the GPS is good at 10Hz define GPS_MAX_RATE_MS 100 + +# 10" DLVR sensor by default +define HAL_AIRSPEED_TYPE_DEFAULT 9 +define AIRSPEED_MAX_SENSORS 1