From 87435473b547a8096234f2ff473278de2fae0a00 Mon Sep 17 00:00:00 2001 From: "Dr.-Ing. Amilcar do Carmo Lucas" Date: Thu, 15 Feb 2024 14:25:44 +0100 Subject: [PATCH] AC_PrecLand: Move accessors code to the .h file --- libraries/AC_PrecLand/AC_PrecLand_Companion.cpp | 17 ----------------- libraries/AC_PrecLand/AC_PrecLand_Companion.h | 6 +++--- libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp | 10 ---------- libraries/AC_PrecLand/AC_PrecLand_IRLock.h | 4 ++-- .../AC_PrecLand/AC_PrecLand_SITL_Gazebo.cpp | 10 ---------- libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.h | 4 ++-- 6 files changed, 7 insertions(+), 44 deletions(-) diff --git a/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp b/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp index 51d46feb77..afb603a7f0 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp @@ -30,23 +30,6 @@ bool AC_PrecLand_Companion::get_los_body(Vector3f& ret) { return false; } -// returns system time in milliseconds of last los measurement -uint32_t AC_PrecLand_Companion::los_meas_time_ms() { - return _los_meas_time_ms; -} - -// return true if there is a valid los measurement available -bool AC_PrecLand_Companion::have_los_meas() -{ - return _have_los_meas; -} - -// return distance to target -float AC_PrecLand_Companion::distance_to_target() -{ - return _distance_to_target; -} - void AC_PrecLand_Companion::handle_msg(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) { _distance_to_target = packet.distance; diff --git a/libraries/AC_PrecLand/AC_PrecLand_Companion.h b/libraries/AC_PrecLand/AC_PrecLand_Companion.h index 892a5aa1f8..ff140b3c16 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Companion.h +++ b/libraries/AC_PrecLand/AC_PrecLand_Companion.h @@ -31,13 +31,13 @@ public: bool get_los_body(Vector3f& ret) override; // returns system time in milliseconds of last los measurement - uint32_t los_meas_time_ms() override; + uint32_t los_meas_time_ms() override { return _los_meas_time_ms; } // return true if there is a valid los measurement available - bool have_los_meas() override; + bool have_los_meas() override { return _have_los_meas; } // returns distance to target in meters (0 means distance is not known) - float distance_to_target() override; + float distance_to_target() override { return _distance_to_target; } // parses a mavlink message from the companion computer void handle_msg(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) override; diff --git a/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp b/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp index e58bb52e82..ac6c8373e7 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp @@ -45,14 +45,4 @@ bool AC_PrecLand_IRLock::get_los_body(Vector3f& ret) { return false; } -// returns system time in milliseconds of last los measurement -uint32_t AC_PrecLand_IRLock::los_meas_time_ms() { - return _los_meas_time_ms; -} - -// return true if there is a valid los measurement available -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 08831bc362..c7c975c2e7 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_IRLock.h +++ b/libraries/AC_PrecLand/AC_PrecLand_IRLock.h @@ -36,10 +36,10 @@ public: bool get_los_body(Vector3f& ret) override; // returns system time in milliseconds of last los measurement - uint32_t los_meas_time_ms() override; + uint32_t los_meas_time_ms() override { return _los_meas_time_ms; } // return true if there is a valid los measurement available - bool have_los_meas() override; + bool have_los_meas() override { return _have_los_meas; } private: #if CONFIG_HAL_BOARD == HAL_BOARD_SITL diff --git a/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.cpp b/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.cpp index 95d331d75b..7bcae4ef09 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.cpp @@ -45,14 +45,4 @@ bool AC_PrecLand_SITL_Gazebo::get_los_body(Vector3f& ret) { return false; } -// returns system time in milliseconds of last los measurement -uint32_t AC_PrecLand_SITL_Gazebo::los_meas_time_ms() { - return _los_meas_time_ms; -} - -// return true if there is a valid los measurement available -bool AC_PrecLand_SITL_Gazebo::have_los_meas() { - return _have_los_meas; -} - #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 dcddec958e..e66b73a688 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.h +++ b/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.h @@ -31,10 +31,10 @@ public: bool get_los_body(Vector3f& ret) override; // returns system time in milliseconds of last los measurement - uint32_t los_meas_time_ms() override; + uint32_t los_meas_time_ms() override { return _los_meas_time_ms; } // return true if there is a valid los measurement available - bool have_los_meas() override; + bool have_los_meas() override { return _have_los_meas; } private: AP_IRLock_SITL_Gazebo irlock;