From 6a3188a8ec544bb1f1e0dd7ce3f06eb68a9a92a4 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 14 Apr 2021 13:16:18 +1000 Subject: [PATCH] AC_PrecLand: use enum-class for Type, make enum private --- libraries/AC_PrecLand/AC_PrecLand.cpp | 12 ++++++------ libraries/AC_PrecLand/AC_PrecLand.h | 20 ++++++++++---------- 2 files changed, 16 insertions(+), 16 deletions(-) diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index 550b2b46df..c842615ad0 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -150,24 +150,24 @@ void AC_PrecLand::init(uint16_t update_rate_hz) } // instantiate backend based on type parameter - switch ((enum PrecLandType)(_type.get())) { + switch ((Type)(_type.get())) { // no type defined - case PRECLAND_TYPE_NONE: + case Type::NONE: default: return; // companion computer - case PRECLAND_TYPE_COMPANION: + case Type::COMPANION: _backend = new AC_PrecLand_Companion(*this, _backend_state); break; // IR Lock - case PRECLAND_TYPE_IRLOCK: + case Type::IRLOCK: _backend = new AC_PrecLand_IRLock(*this, _backend_state); break; #if CONFIG_HAL_BOARD == HAL_BOARD_SITL - case PRECLAND_TYPE_SITL_GAZEBO: + case Type::SITL_GAZEBO: _backend = new AC_PrecLand_SITL_Gazebo(*this, _backend_state); break; - case PRECLAND_TYPE_SITL: + case Type::SITL: _backend = new AC_PrecLand_SITL(*this, _backend_state); break; #endif diff --git a/libraries/AC_PrecLand/AC_PrecLand.h b/libraries/AC_PrecLand/AC_PrecLand.h index d6f9e4b3e9..2681756842 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.h +++ b/libraries/AC_PrecLand/AC_PrecLand.h @@ -29,15 +29,6 @@ public: AC_PrecLand(const AC_PrecLand &other) = delete; AC_PrecLand &operator=(const AC_PrecLand&) = delete; - // types of precision landing (used for PRECLAND_TYPE parameter) - enum PrecLandType { - PRECLAND_TYPE_NONE = 0, - PRECLAND_TYPE_COMPANION, - PRECLAND_TYPE_IRLOCK, - PRECLAND_TYPE_SITL_GAZEBO, - PRECLAND_TYPE_SITL, - }; - // perform any required initialisation of landing controllers // update_rate_hz should be the rate at which the update method will be called in hz void init(uint16_t update_rate_hz); @@ -87,6 +78,15 @@ private: KALMAN_FILTER = 1, }; + // types of precision landing (used for PRECLAND_TYPE parameter) + enum class Type : uint8_t { + NONE = 0, + COMPANION = 1, + IRLOCK = 2, + SITL_GAZEBO = 3, + SITL = 4, + }; + // run target position estimator void run_estimator(float rangefinder_alt_m, bool rangefinder_alt_valid); @@ -102,7 +102,7 @@ private: // parameters AP_Int8 _enabled; // enabled/disabled - AP_Int8 _type; // precision landing sensor type + AP_Enum _type; // precision landing sensor type AP_Int8 _bus; // which sensor bus AP_Enum _estimator_type; // precision landing estimator type AP_Float _lag; // sensor lag in seconds