mirror of https://github.com/ArduPilot/ardupilot
AC_PrecLand: fixes for feature disablement
This commit is contained in:
parent
9643f44ecc
commit
09dbf53454
|
@ -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;
|
||||
|
|
|
@ -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 {
|
||||
|
|
Loading…
Reference in New Issue