From 5dd5c22c39d5ab0d053a569900490ef481504be2 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 16 Mar 2017 17:02:52 +0900 Subject: [PATCH] AC_PrecLand: build IRLock on all boards --- libraries/AC_PrecLand/AC_PrecLand.cpp | 2 -- libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp | 5 ----- libraries/AC_PrecLand/AC_PrecLand_IRLock.h | 4 ---- 3 files changed, 11 deletions(-) diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index 670f620687..cc12fc209c 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -104,11 +104,9 @@ void AC_PrecLand::init() _backend = new AC_PrecLand_Companion(*this, _backend_state); break; // IR Lock -#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN case PRECLAND_TYPE_IRLOCK: _backend = new AC_PrecLand_IRLock(*this, _backend_state); break; -#endif #if CONFIG_HAL_BOARD == HAL_BOARD_SITL case PRECLAND_TYPE_SITL_GAZEBO: _backend = new AC_PrecLand_SITL_Gazebo(*this, _backend_state); diff --git a/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp b/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp index 5d3c17a56b..6e90f9a772 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp @@ -3,9 +3,6 @@ extern const AP_HAL::HAL& hal; -// this only builds for PX4 so far -#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN || CONFIG_HAL_BOARD == HAL_BOARD_SITL - // Constructor AC_PrecLand_IRLock::AC_PrecLand_IRLock(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state) : AC_PrecLand_Backend(frontend, state), @@ -57,5 +54,3 @@ uint32_t AC_PrecLand_IRLock::los_meas_time_ms() { bool AC_PrecLand_IRLock::have_los_meas() { return _have_los_meas; } - -#endif // PX4 diff --git a/libraries/AC_PrecLand/AC_PrecLand_IRLock.h b/libraries/AC_PrecLand/AC_PrecLand_IRLock.h index 61de6484ab..bcf78f57c2 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_IRLock.h +++ b/libraries/AC_PrecLand/AC_PrecLand_IRLock.h @@ -9,9 +9,6 @@ #include #endif -// this only builds for PX4 so far -#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN || CONFIG_HAL_BOARD == HAL_BOARD_SITL - /* * AC_PrecLand_IRLock - implements precision landing using target vectors provided * by a companion computer (i.e. Odroid) communicating via MAVLink @@ -47,4 +44,3 @@ private: bool _have_los_meas; // true if there is a valid measurement from the camera uint32_t _los_meas_time_ms; // system time in milliseconds when los was measured }; -#endif