mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
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:
|
default:
|
||||||
return;
|
return;
|
||||||
// companion computer
|
// companion computer
|
||||||
|
#if AC_PRECLAND_COMPANION_ENABLED
|
||||||
case Type::COMPANION:
|
case Type::COMPANION:
|
||||||
_backend = new AC_PrecLand_Companion(*this, _backend_state);
|
_backend = new AC_PrecLand_Companion(*this, _backend_state);
|
||||||
break;
|
break;
|
||||||
// IR Lock
|
// IR Lock
|
||||||
|
#endif
|
||||||
|
#if AC_PRECLAND_IRLOCK_ENABLED
|
||||||
case Type::IRLOCK:
|
case Type::IRLOCK:
|
||||||
_backend = new AC_PrecLand_IRLock(*this, _backend_state);
|
_backend = new AC_PrecLand_IRLock(*this, _backend_state);
|
||||||
break;
|
break;
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#endif
|
||||||
|
#if AC_PRECLAND_SITL_GAZEBO_ENABLED
|
||||||
case Type::SITL_GAZEBO:
|
case Type::SITL_GAZEBO:
|
||||||
_backend = new AC_PrecLand_SITL_Gazebo(*this, _backend_state);
|
_backend = new AC_PrecLand_SITL_Gazebo(*this, _backend_state);
|
||||||
break;
|
break;
|
||||||
|
#endif
|
||||||
|
#if AC_PRECLAND_SITL_ENABLED
|
||||||
case Type::SITL:
|
case Type::SITL:
|
||||||
_backend = new AC_PrecLand_SITL(*this, _backend_state);
|
_backend = new AC_PrecLand_SITL(*this, _backend_state);
|
||||||
break;
|
break;
|
||||||
|
@ -127,10 +127,18 @@ private:
|
|||||||
// types of precision landing (used for PRECLAND_TYPE parameter)
|
// types of precision landing (used for PRECLAND_TYPE parameter)
|
||||||
enum class Type : uint8_t {
|
enum class Type : uint8_t {
|
||||||
NONE = 0,
|
NONE = 0,
|
||||||
|
#if AC_PRECLAND_COMPANION_ENABLED
|
||||||
COMPANION = 1,
|
COMPANION = 1,
|
||||||
|
#endif
|
||||||
|
#if AC_PRECLAND_IRLOCK_ENABLED
|
||||||
IRLOCK = 2,
|
IRLOCK = 2,
|
||||||
|
#endif
|
||||||
|
#if AC_PRECLAND_SITL_GAZEBO_ENABLED
|
||||||
SITL_GAZEBO = 3,
|
SITL_GAZEBO = 3,
|
||||||
|
#endif
|
||||||
|
#if AC_PRECLAND_SITL_ENABLED
|
||||||
SITL = 4,
|
SITL = 4,
|
||||||
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
enum PLndOptions {
|
enum PLndOptions {
|
||||||
|
Loading…
Reference in New Issue
Block a user