AC_Precland: fixed build under cygwin
the IRLock driver only builds on PX4 at the moment
This commit is contained in:
parent
6ec532694d
commit
2ce0f4c171
@ -75,9 +75,11 @@ 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
|
||||
}
|
||||
|
||||
// init backend
|
||||
|
@ -4,6 +4,9 @@
|
||||
|
||||
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
|
||||
|
||||
// Constructor
|
||||
AC_PrecLand_IRLock::AC_PrecLand_IRLock(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state)
|
||||
: AC_PrecLand_Backend(frontend, state),
|
||||
@ -35,3 +38,5 @@ bool AC_PrecLand_IRLock::get_angle_to_target(float &x_angle_rad, float &y_angle_
|
||||
{
|
||||
return irlock.get_angle_to_target(x_angle_rad, y_angle_rad);
|
||||
}
|
||||
|
||||
#endif // PX4
|
||||
|
@ -7,6 +7,9 @@
|
||||
#include <AC_PrecLand/AC_PrecLand_Backend.h>
|
||||
#include <AP_IRLock/AP_IRLock.h>
|
||||
|
||||
// this only builds for PX4 so far
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
|
||||
/*
|
||||
* AC_PrecLand_IRLock - implements precision landing using target vectors provided
|
||||
* by a companion computer (i.e. Odroid) communicating via MAVLink
|
||||
@ -36,4 +39,5 @@ private:
|
||||
AP_IRLock_PX4 irlock;
|
||||
|
||||
};
|
||||
#endif
|
||||
#endif // __AC_PRECLAND_IRLOCK_H__
|
||||
|
Loading…
Reference in New Issue
Block a user