mirror of https://github.com/ArduPilot/ardupilot
AP_Airspeed: allow hwdef override of airspeed default type
This commit is contained in:
parent
fdff355a8a
commit
a20d3fed94
|
@ -37,7 +37,12 @@
|
|||
|
||||
extern const AP_HAL::HAL &hal;
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#ifdef HAL_AIRSPEED_TYPE_DEFAULT
|
||||
#define ARSPD_DEFAULT_TYPE HAL_AIRSPEED_TYPE_DEFAULT
|
||||
#ifndef ARSPD_DEFAULT_PIN
|
||||
#define ARSPD_DEFAULT_PIN 1
|
||||
#endif
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#define ARSPD_DEFAULT_TYPE TYPE_ANALOG
|
||||
#define ARSPD_DEFAULT_PIN 1
|
||||
#elif APM_BUILD_TYPE(APM_BUILD_Rover)
|
||||
|
|
Loading…
Reference in New Issue