AP_Airspeed: disable airspeed (_TYPE=0) as rover default

This commit is contained in:
Tom Pittenger 2019-02-06 18:01:33 -07:00 committed by Randy Mackay
parent 937e05bb2a
commit 95c903c7cf
1 changed files with 3 additions and 0 deletions

View File

@ -40,6 +40,9 @@ extern const AP_HAL::HAL &hal;
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#define ARSPD_DEFAULT_TYPE TYPE_ANALOG
#define ARSPD_DEFAULT_PIN 1
#elif APM_BUILD_TYPE(APM_BUILD_APMrover2)
#define ARSPD_DEFAULT_TYPE TYPE_NONE
#define ARSPD_DEFAULT_PIN 15
#else
#define ARSPD_DEFAULT_TYPE TYPE_I2C_MS4525
#define ARSPD_DEFAULT_PIN 15