mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: make AP_RANGEFINDER_ENABLED remove more code
This commit is contained in:
parent
abc0179a53
commit
a715ee1ce2
|
@ -342,6 +342,7 @@
|
||||||
#define AP_COMPASS_ENABLED defined(HAL_PERIPH_ENABLE_MAG)
|
#define AP_COMPASS_ENABLED defined(HAL_PERIPH_ENABLE_MAG)
|
||||||
#define AP_BARO_ENABLED defined(HAL_PERIPH_ENABLE_BARO)
|
#define AP_BARO_ENABLED defined(HAL_PERIPH_ENABLE_BARO)
|
||||||
#define AP_GPS_ENABLED defined(HAL_PERIPH_ENABLE_GPS)
|
#define AP_GPS_ENABLED defined(HAL_PERIPH_ENABLE_GPS)
|
||||||
|
#define AP_RANGEFINDER_ENABLED defined(HAL_PERIPH_ENABLE_RANGEFINDER)
|
||||||
#define AP_RPM_ENABLED defined(HAL_PERIPH_ENABLE_RPM)
|
#define AP_RPM_ENABLED defined(HAL_PERIPH_ENABLE_RPM)
|
||||||
#define AP_RCPROTOCOL_ENABLED defined(HAL_PERIPH_ENABLE_RCIN)
|
#define AP_RCPROTOCOL_ENABLED defined(HAL_PERIPH_ENABLE_RCIN)
|
||||||
#define AP_RTC_ENABLED defined(HAL_PERIPH_ENABLE_RTC)
|
#define AP_RTC_ENABLED defined(HAL_PERIPH_ENABLE_RTC)
|
||||||
|
|
|
@ -131,8 +131,9 @@ define BARO_MAX_INSTANCES 1
|
||||||
define INS_MAX_INSTANCES 1
|
define INS_MAX_INSTANCES 1
|
||||||
|
|
||||||
# SkyViper doesn't have any rangefinder, but might get mavlink?
|
# SkyViper doesn't have any rangefinder, but might get mavlink?
|
||||||
|
define AP_RANGEFINDER_ENABLED 1
|
||||||
define AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED 0
|
define AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED 0
|
||||||
define AP_RANGEFINDER_MAVLINK_ENABLED 1
|
define AP_RANGEFINDER_MAVLINK_ENABLED AP_RANGEFINDER_ENABLED
|
||||||
|
|
||||||
# SkyViper doesn't have RPM sensors:
|
# SkyViper doesn't have RPM sensors:
|
||||||
define AP_RPM_ENABLED 0
|
define AP_RPM_ENABLED 0
|
||||||
|
|
Loading…
Reference in New Issue