AC_PrecLand: build IRLock on all boards

This commit is contained in:
Randy Mackay 2017-03-16 17:02:52 +09:00
parent 1fb6d468c6
commit 5dd5c22c39
3 changed files with 0 additions and 11 deletions

View File

@ -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);

View File

@ -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

View File

@ -9,9 +9,6 @@
#include <AP_IRLock/AP_IRLock_SITL.h>
#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