diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index b2e2212239..398286b878 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -241,17 +241,23 @@ void AC_PrecLand::init(uint16_t update_rate_hz) default: return; // companion computer +#if AC_PRECLAND_COMPANION_ENABLED case Type::COMPANION: _backend = new AC_PrecLand_Companion(*this, _backend_state); break; // IR Lock +#endif +#if AC_PRECLAND_IRLOCK_ENABLED case Type::IRLOCK: _backend = new AC_PrecLand_IRLock(*this, _backend_state); break; -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#endif +#if AC_PRECLAND_SITL_GAZEBO_ENABLED case Type::SITL_GAZEBO: _backend = new AC_PrecLand_SITL_Gazebo(*this, _backend_state); break; +#endif +#if AC_PRECLAND_SITL_ENABLED case Type::SITL: _backend = new AC_PrecLand_SITL(*this, _backend_state); break; diff --git a/libraries/AC_PrecLand/AC_PrecLand.h b/libraries/AC_PrecLand/AC_PrecLand.h index 397739c9f7..6826bded51 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.h +++ b/libraries/AC_PrecLand/AC_PrecLand.h @@ -127,10 +127,18 @@ private: // types of precision landing (used for PRECLAND_TYPE parameter) enum class Type : uint8_t { NONE = 0, +#if AC_PRECLAND_COMPANION_ENABLED COMPANION = 1, +#endif +#if AC_PRECLAND_IRLOCK_ENABLED IRLOCK = 2, +#endif +#if AC_PRECLAND_SITL_GAZEBO_ENABLED SITL_GAZEBO = 3, +#endif +#if AC_PRECLAND_SITL_ENABLED SITL = 4, +#endif }; enum PLndOptions {