mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Airspeed: allow setting of default airspeed pin
This commit is contained in:
parent
585631a22d
commit
1ffc2cbe41
@ -45,8 +45,12 @@ extern const AP_HAL::HAL &hal;
|
|||||||
#define ARSPD_DEFAULT_PIN 15
|
#define ARSPD_DEFAULT_PIN 15
|
||||||
#else
|
#else
|
||||||
#define ARSPD_DEFAULT_TYPE TYPE_I2C_MS4525
|
#define ARSPD_DEFAULT_TYPE TYPE_I2C_MS4525
|
||||||
|
#ifdef HAL_DEFAULT_AIRSPEED_PIN
|
||||||
|
#define ARSPD_DEFAULT_PIN HAL_DEFAULT_AIRSPEED_PIN
|
||||||
|
#else
|
||||||
#define ARSPD_DEFAULT_PIN 15
|
#define ARSPD_DEFAULT_PIN 15
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
||||||
#define PSI_RANGE_DEFAULT 0.05
|
#define PSI_RANGE_DEFAULT 0.05
|
||||||
|
Loading…
Reference in New Issue
Block a user