From a91178d0e1dd297165e66d1c6361560afbee83ae Mon Sep 17 00:00:00 2001 From: tzarjakob Date: Wed, 22 Mar 2023 09:45:41 +0100 Subject: [PATCH] AC_PrecLand: configuration of Precision Landing for custom build server --- libraries/AC_PrecLand/AC_PrecLand.cpp | 9 ++++++- libraries/AC_PrecLand/AC_PrecLand.h | 8 +++++- libraries/AC_PrecLand/AC_PrecLand_Backend.h | 9 ++++++- .../AC_PrecLand/AC_PrecLand_Companion.cpp | 8 +++++- libraries/AC_PrecLand/AC_PrecLand_Companion.h | 9 ++++++- libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp | 8 +++++- libraries/AC_PrecLand/AC_PrecLand_IRLock.h | 9 ++++++- libraries/AC_PrecLand/AC_PrecLand_SITL.cpp | 4 +-- libraries/AC_PrecLand/AC_PrecLand_SITL.h | 9 ++++--- .../AC_PrecLand/AC_PrecLand_SITL_Gazebo.cpp | 4 +-- .../AC_PrecLand/AC_PrecLand_SITL_Gazebo.h | 9 ++++--- .../AC_PrecLand/AC_PrecLand_StateMachine.cpp | 8 +++++- .../AC_PrecLand/AC_PrecLand_StateMachine.h | 7 +++++ libraries/AC_PrecLand/AC_PrecLand_config.h | 27 +++++++++++++++++++ 14 files changed, 110 insertions(+), 18 deletions(-) create mode 100644 libraries/AC_PrecLand/AC_PrecLand_config.h diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index cf23c85549..b2e2212239 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -1,7 +1,12 @@ +#include "AC_PrecLand_config.h" + +#if AC_PRECLAND_ENABLED + +#include "AC_PrecLand.h" #include #include #include -#include "AC_PrecLand.h" + #include "AC_PrecLand_Backend.h" #include "AC_PrecLand_Companion.h" #include "AC_PrecLand_IRLock.h" @@ -774,3 +779,5 @@ AC_PrecLand *ac_precland() } } + +#endif // AC_PRECLAND_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand.h b/libraries/AC_PrecLand/AC_PrecLand.h index 2f804f59c9..397739c9f7 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.h +++ b/libraries/AC_PrecLand/AC_PrecLand.h @@ -1,7 +1,11 @@ #pragma once -#include +#include "AC_PrecLand_config.h" + +#if AC_PRECLAND_ENABLED + #include +#include #include #include "PosVelEKF.h" #include @@ -231,3 +235,5 @@ private: namespace AP { AC_PrecLand *ac_precland(); }; + +#endif // AC_PRECLAND_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand_Backend.h b/libraries/AC_PrecLand/AC_PrecLand_Backend.h index d816a85d8d..41facd0deb 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Backend.h +++ b/libraries/AC_PrecLand/AC_PrecLand_Backend.h @@ -1,8 +1,13 @@ #pragma once +#include "AC_PrecLand_config.h" + +#if AC_PRECLAND_ENABLED + +#include "AC_PrecLand.h" #include #include -#include "AC_PrecLand.h" + class AC_PrecLand_Backend { @@ -44,3 +49,5 @@ protected: const AC_PrecLand& _frontend; // reference to precision landing front end AC_PrecLand::precland_state &_state; // reference to this instances state }; + +#endif // AC_PRECLAND_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp b/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp index e65ff1d686..51d46feb77 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp @@ -1,6 +1,10 @@ +#include "AC_PrecLand_config.h" + +#if AC_PRECLAND_COMPANION_ENABLED + +#include "AC_PrecLand_Companion.h" #include #include -#include "AC_PrecLand_Companion.h" // perform any required initialisation of backend void AC_PrecLand_Companion::init() @@ -73,3 +77,5 @@ void AC_PrecLand_Companion::handle_msg(const mavlink_landing_target_t &packet, u _los_meas_time_ms = timestamp_ms; _have_los_meas = true; } + +#endif // AC_PRECLAND_COMPANION_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand_Companion.h b/libraries/AC_PrecLand/AC_PrecLand_Companion.h index 67af707a9b..892a5aa1f8 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Companion.h +++ b/libraries/AC_PrecLand/AC_PrecLand_Companion.h @@ -1,7 +1,11 @@ #pragma once -#include +#include "AC_PrecLand_config.h" + +#if AC_PRECLAND_COMPANION_ENABLED + #include "AC_PrecLand_Backend.h" +#include /* * AC_PrecLand_Companion - implements precision landing using target vectors provided @@ -46,3 +50,6 @@ private: uint32_t _los_meas_time_ms; // system time in milliseconds when los was measured bool _wrong_frame_msg_sent; }; + + +#endif // AC_PRECLAND_COMPANION_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp b/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp index 04b1126621..e58bb52e82 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp @@ -1,5 +1,9 @@ -#include +#include "AC_PrecLand_config.h" + +#if AC_PRECLAND_IRLOCK_ENABLED + #include "AC_PrecLand_IRLock.h" +#include // Constructor AC_PrecLand_IRLock::AC_PrecLand_IRLock(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state) @@ -50,3 +54,5 @@ uint32_t AC_PrecLand_IRLock::los_meas_time_ms() { bool AC_PrecLand_IRLock::have_los_meas() { return _have_los_meas; } + +#endif // AC_PRECLAND_IRLOCK_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand_IRLock.h b/libraries/AC_PrecLand/AC_PrecLand_IRLock.h index da2923b126..08831bc362 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_IRLock.h +++ b/libraries/AC_PrecLand/AC_PrecLand_IRLock.h @@ -1,7 +1,12 @@ #pragma once -#include +#include "AC_PrecLand_config.h" + +#if AC_PRECLAND_IRLOCK_ENABLED + #include +#include + #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include #else @@ -46,3 +51,5 @@ 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 // AC_PRECLAND_IRLOCK_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand_SITL.cpp b/libraries/AC_PrecLand/AC_PrecLand_SITL.cpp index b71a4d1c26..1d920818fb 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_SITL.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_SITL.cpp @@ -1,7 +1,7 @@ #include #include "AC_PrecLand_SITL.h" -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#if AC_PRECLAND_SITL_ENABLED #include "AP_AHRS/AP_AHRS.h" // init - perform initialisation of this backend @@ -54,4 +54,4 @@ bool AC_PrecLand_SITL::get_los_body(Vector3f& ret) { return true; } -#endif +#endif // AC_PRECLAND_SITL_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand_SITL.h b/libraries/AC_PrecLand/AC_PrecLand_SITL.h index ee6fd526ed..53b0c23aa6 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_SITL.h +++ b/libraries/AC_PrecLand/AC_PrecLand_SITL.h @@ -1,8 +1,11 @@ #pragma once -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL -#include +#include "AC_PrecLand_config.h" + +#if AC_PRECLAND_SITL_ENABLED + #include +#include #include /* @@ -43,4 +46,4 @@ private: float _distance_to_target; // distance to target in meters }; -#endif +#endif // AC_PRECLAND_SITL_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.cpp b/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.cpp index 2bf94759dc..95d331d75b 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.cpp @@ -3,7 +3,7 @@ extern const AP_HAL::HAL& hal; -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#if AC_PRECLAND_SITL_GAZEBO_ENABLED // Constructor AC_PrecLand_SITL_Gazebo::AC_PrecLand_SITL_Gazebo(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state) @@ -55,4 +55,4 @@ bool AC_PrecLand_SITL_Gazebo::have_los_meas() { return _have_los_meas; } -#endif +#endif // AC_PRECLAND_SITL_GAZEBO_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.h b/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.h index e7f1ab06ed..dcddec958e 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.h +++ b/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.h @@ -1,8 +1,11 @@ #pragma once -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL -#include +#include "AC_PrecLand_config.h" + +#if AC_PRECLAND_SITL_GAZEBO_ENABLED + #include +#include #include /* @@ -41,4 +44,4 @@ private: uint32_t _los_meas_time_ms; // system time in milliseconds when los was measured }; -#endif +#endif // AC_PRECLAND_SITL_GAZEBO_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand_StateMachine.cpp b/libraries/AC_PrecLand/AC_PrecLand_StateMachine.cpp index e2d3615651..c456288ca2 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_StateMachine.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_StateMachine.cpp @@ -1,5 +1,9 @@ -#include "AC_PrecLand_StateMachine.h" +#include "AC_PrecLand_config.h" + +#if AC_PRECLAND_ENABLED + #include +#include "AC_PrecLand_StateMachine.h" #include #include @@ -274,3 +278,5 @@ AC_PrecLand_StateMachine::FailSafeAction AC_PrecLand_StateMachine::get_failsafe_ // should never reach here return FailSafeAction::DESCEND; } + +#endif // AC_PRECLAND_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand_StateMachine.h b/libraries/AC_PrecLand/AC_PrecLand_StateMachine.h index b72b0e8d72..8479be3c6a 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_StateMachine.h +++ b/libraries/AC_PrecLand/AC_PrecLand_StateMachine.h @@ -1,5 +1,10 @@ #pragma once +#include "AC_PrecLand_config.h" + +#if AC_PRECLAND_ENABLED + +#include #include // This class constantly monitors what the status of the landing target is @@ -101,3 +106,5 @@ private: uint32_t failsafe_start_ms; // timestamp of when failsafe was triggered }; + +#endif // AC_PRECLAND_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand_config.h b/libraries/AC_PrecLand/AC_PrecLand_config.h new file mode 100644 index 0000000000..74a5043955 --- /dev/null +++ b/libraries/AC_PrecLand/AC_PrecLand_config.h @@ -0,0 +1,27 @@ +#pragma once + +#include + +#ifndef AC_PRECLAND_ENABLED +#define AC_PRECLAND_ENABLED 1 +#endif + +#ifndef AC_PRECLAND_BACKEND_DEFAULT_ENABLED +#define AC_PRECLAND_BACKEND_DEFAULT_ENABLED AC_PRECLAND_ENABLED +#endif + +#ifndef AC_PRECLAND_COMPANION_ENABLED +#define AC_PRECLAND_COMPANION_ENABLED AC_PRECLAND_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AC_PRECLAND_IRLOCK_ENABLED +#define AC_PRECLAND_IRLOCK_ENABLED AC_PRECLAND_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AC_PRECLAND_SITL_ENABLED +#define AC_PRECLAND_SITL_ENABLED (AC_PRECLAND_BACKEND_DEFAULT_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_SITL) +#endif + +#ifndef AC_PRECLAND_SITL_GAZEBO_ENABLED +#define AC_PRECLAND_SITL_GAZEBO_ENABLED (AC_PRECLAND_BACKEND_DEFAULT_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_SITL) +#endif