From 8fe16f5627955261a07c758a2814a27af98e0e90 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Sep 2019 18:58:52 +1000 Subject: [PATCH] AP_Proximity: use enum class for status --- libraries/AP_Proximity/AP_Proximity.cpp | 14 +++++++------- libraries/AP_Proximity/AP_Proximity.h | 14 +++++++------- libraries/AP_Proximity/AP_Proximity_AirSimSITL.cpp | 4 ++-- libraries/AP_Proximity/AP_Proximity_Backend.cpp | 4 ++-- libraries/AP_Proximity/AP_Proximity_Backend.h | 2 +- .../AP_Proximity/AP_Proximity_LightWareSF40C.cpp | 4 ++-- libraries/AP_Proximity/AP_Proximity_MAV.cpp | 4 ++-- libraries/AP_Proximity/AP_Proximity_MorseSITL.cpp | 4 ++-- libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp | 4 ++-- .../AP_Proximity/AP_Proximity_RangeFinder.cpp | 6 +++--- libraries/AP_Proximity/AP_Proximity_SITL.cpp | 4 ++-- .../AP_Proximity/AP_Proximity_TeraRangerTower.cpp | 4 ++-- .../AP_Proximity_TeraRangerTowerEvo.cpp | 4 ++-- 13 files changed, 36 insertions(+), 36 deletions(-) diff --git a/libraries/AP_Proximity/AP_Proximity.cpp b/libraries/AP_Proximity/AP_Proximity.cpp index 0e0fc0a605..6c85ab6915 100644 --- a/libraries/AP_Proximity/AP_Proximity.cpp +++ b/libraries/AP_Proximity/AP_Proximity.cpp @@ -206,7 +206,7 @@ void AP_Proximity::init(void) } // initialise status - state[i].status = Proximity_NotConnected; + state[i].status = Status::NotConnected; } } @@ -222,7 +222,7 @@ void AP_Proximity::update(void) // work out primary instance - first sensor returning good data for (int8_t i=num_instances-1; i>=0; i--) { - if (drivers[i] != nullptr && (state[i].status == Proximity_Good)) { + if (drivers[i] != nullptr && (state[i].status == Status::Good)) { primary_instance = i; } } @@ -249,17 +249,17 @@ int16_t AP_Proximity::get_yaw_correction(uint8_t instance) const } // return sensor health -AP_Proximity::Proximity_Status AP_Proximity::get_status(uint8_t instance) const +AP_Proximity::Status AP_Proximity::get_status(uint8_t instance) const { // sanity check instance number if (!valid_instance(instance)) { - return Proximity_NotConnected; + return Status::NotConnected; } return state[instance].status; } -AP_Proximity::Proximity_Status AP_Proximity::get_status() const +AP_Proximity::Status AP_Proximity::get_status() const { return get_status(primary_instance); } @@ -458,7 +458,7 @@ AP_Proximity::Type AP_Proximity::get_type(uint8_t instance) const bool AP_Proximity::sensor_present() const { - return get_status() != Proximity_NotConnected; + return get_status() != Status::NotConnected; } bool AP_Proximity::sensor_enabled() const { @@ -466,7 +466,7 @@ bool AP_Proximity::sensor_enabled() const } bool AP_Proximity::sensor_failed() const { - return get_status() != Proximity_Good; + return get_status() != Status::Good; } AP_Proximity *AP_Proximity::_singleton; diff --git a/libraries/AP_Proximity/AP_Proximity.h b/libraries/AP_Proximity/AP_Proximity.h index f0195e6e5b..4c50823227 100644 --- a/libraries/AP_Proximity/AP_Proximity.h +++ b/libraries/AP_Proximity/AP_Proximity.h @@ -53,10 +53,10 @@ public: #endif }; - enum Proximity_Status { - Proximity_NotConnected = 0, - Proximity_NoData, - Proximity_Good + enum Status { + NotConnected = 0, + NoData, + Good }; // structure holding distances in PROXIMITY_MAX_DIRECTION directions. used for sending distances to ground station @@ -80,8 +80,8 @@ public: int16_t get_yaw_correction(uint8_t instance) const; // return sensor health - Proximity_Status get_status(uint8_t instance) const; - Proximity_Status get_status() const; + Status get_status(uint8_t instance) const; + Status get_status() const; // Return the number of proximity sensors uint8_t num_sensors(void) const { @@ -119,7 +119,7 @@ public: // The Proximity_State structure is filled in by the backend driver struct Proximity_State { uint8_t instance; // the instance number of this proximity sensor - enum Proximity_Status status; // sensor status + Status status; // sensor status }; // diff --git a/libraries/AP_Proximity/AP_Proximity_AirSimSITL.cpp b/libraries/AP_Proximity/AP_Proximity_AirSimSITL.cpp index ec79b013bd..fcf0dbec5a 100644 --- a/libraries/AP_Proximity/AP_Proximity_AirSimSITL.cpp +++ b/libraries/AP_Proximity/AP_Proximity_AirSimSITL.cpp @@ -38,11 +38,11 @@ void AP_Proximity_AirSimSITL::update(void) { SITL::vector3f_array &points = sitl->state.scanner.points; if (points.length == 0) { - set_status(AP_Proximity::Proximity_NoData); + set_status(AP_Proximity::Status::NoData); return; } - set_status(AP_Proximity::Proximity_Good); + set_status(AP_Proximity::Status::Good); memset(_distance_valid, 0, sizeof(_distance_valid)); memset(_angle, 0, sizeof(_angle)); diff --git a/libraries/AP_Proximity/AP_Proximity_Backend.cpp b/libraries/AP_Proximity/AP_Proximity_Backend.cpp index d9b5f63529..e3d273e3a4 100644 --- a/libraries/AP_Proximity/AP_Proximity_Backend.cpp +++ b/libraries/AP_Proximity/AP_Proximity_Backend.cpp @@ -142,7 +142,7 @@ bool AP_Proximity_Backend::get_horizontal_distances(AP_Proximity::Proximity_Dist const Vector2f* AP_Proximity_Backend::get_boundary_points(uint16_t& num_points) const { // high-level status check - if (state.status != AP_Proximity::Proximity_Good) { + if (state.status != AP_Proximity::Status::Good) { num_points = 0; return nullptr; } @@ -236,7 +236,7 @@ void AP_Proximity_Backend::update_boundary_for_sector(const uint8_t sector, cons } // set status and update valid count -void AP_Proximity_Backend::set_status(AP_Proximity::Proximity_Status status) +void AP_Proximity_Backend::set_status(AP_Proximity::Status status) { state.status = status; } diff --git a/libraries/AP_Proximity/AP_Proximity_Backend.h b/libraries/AP_Proximity/AP_Proximity_Backend.h index 67b3bcd218..5741bd4750 100644 --- a/libraries/AP_Proximity/AP_Proximity_Backend.h +++ b/libraries/AP_Proximity/AP_Proximity_Backend.h @@ -68,7 +68,7 @@ public: protected: // set status and update valid_count - void set_status(AP_Proximity::Proximity_Status status); + void set_status(AP_Proximity::Status status); // find which sector a given angle falls into bool convert_angle_to_sector(float angle_degrees, uint8_t §or) const; diff --git a/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp b/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp index 32c4e2af95..a245d55b85 100644 --- a/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp +++ b/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp @@ -63,9 +63,9 @@ void AP_Proximity_LightWareSF40C::update(void) // check for timeout and set health status if ((_last_distance_received_ms == 0) || (AP_HAL::millis() - _last_distance_received_ms > PROXIMITY_SF40C_TIMEOUT_MS)) { - set_status(AP_Proximity::Proximity_NoData); + set_status(AP_Proximity::Status::NoData); } else { - set_status(AP_Proximity::Proximity_Good); + set_status(AP_Proximity::Status::Good); } } diff --git a/libraries/AP_Proximity/AP_Proximity_MAV.cpp b/libraries/AP_Proximity/AP_Proximity_MAV.cpp index 3e182cca06..428fe7f0b4 100644 --- a/libraries/AP_Proximity/AP_Proximity_MAV.cpp +++ b/libraries/AP_Proximity/AP_Proximity_MAV.cpp @@ -40,9 +40,9 @@ void AP_Proximity_MAV::update(void) // check for timeout and set health status if ((_last_update_ms == 0 || (AP_HAL::millis() - _last_update_ms > PROXIMITY_MAV_TIMEOUT_MS)) && (_last_upward_update_ms == 0 || (AP_HAL::millis() - _last_upward_update_ms > PROXIMITY_MAV_TIMEOUT_MS))) { - set_status(AP_Proximity::Proximity_NoData); + set_status(AP_Proximity::Status::NoData); } else { - set_status(AP_Proximity::Proximity_Good); + set_status(AP_Proximity::Status::Good); } } diff --git a/libraries/AP_Proximity/AP_Proximity_MorseSITL.cpp b/libraries/AP_Proximity/AP_Proximity_MorseSITL.cpp index dea8ac5ea4..1cd54d370d 100644 --- a/libraries/AP_Proximity/AP_Proximity_MorseSITL.cpp +++ b/libraries/AP_Proximity/AP_Proximity_MorseSITL.cpp @@ -41,11 +41,11 @@ void AP_Proximity_MorseSITL::update(void) SITL::float_array &ranges = sitl->state.scanner.ranges; if (points.length != ranges.length || points.length == 0) { - set_status(AP_Proximity::Proximity_NoData); + set_status(AP_Proximity::Status::NoData); return; } - set_status(AP_Proximity::Proximity_Good); + set_status(AP_Proximity::Status::Good); memset(_distance_valid, 0, sizeof(_distance_valid)); memset(_angle, 0, sizeof(_angle)); diff --git a/libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp b/libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp index 171ad9685c..6e7697053d 100644 --- a/libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp +++ b/libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp @@ -109,10 +109,10 @@ void AP_Proximity_RPLidarA2::update(void) // check for timeout and set health status if ((_last_distance_received_ms == 0) || (AP_HAL::millis() - _last_distance_received_ms > COMM_ACTIVITY_TIMEOUT_MS)) { - set_status(AP_Proximity::Proximity_NoData); + set_status(AP_Proximity::Status::NoData); Debug(1, "LIDAR NO DATA"); } else { - set_status(AP_Proximity::Proximity_Good); + set_status(AP_Proximity::Status::Good); } } diff --git a/libraries/AP_Proximity/AP_Proximity_RangeFinder.cpp b/libraries/AP_Proximity/AP_Proximity_RangeFinder.cpp index 9c78097761..9d281d4f3d 100644 --- a/libraries/AP_Proximity/AP_Proximity_RangeFinder.cpp +++ b/libraries/AP_Proximity/AP_Proximity_RangeFinder.cpp @@ -35,7 +35,7 @@ void AP_Proximity_RangeFinder::update(void) // exit immediately if no rangefinder object const RangeFinder *rngfnd = frontend.get_rangefinder(); if (rngfnd == nullptr) { - set_status(AP_Proximity::Proximity_NoData); + set_status(AP_Proximity::Status::NoData); return; } @@ -76,9 +76,9 @@ void AP_Proximity_RangeFinder::update(void) // check for timeout and set health status if ((_last_update_ms == 0) || (now - _last_update_ms > PROXIMITY_RANGEFIDER_TIMEOUT_MS)) { - set_status(AP_Proximity::Proximity_NoData); + set_status(AP_Proximity::Status::NoData); } else { - set_status(AP_Proximity::Proximity_Good); + set_status(AP_Proximity::Status::Good); } } diff --git a/libraries/AP_Proximity/AP_Proximity_SITL.cpp b/libraries/AP_Proximity/AP_Proximity_SITL.cpp index 0fc2af602f..7d7d5006a7 100644 --- a/libraries/AP_Proximity/AP_Proximity_SITL.cpp +++ b/libraries/AP_Proximity/AP_Proximity_SITL.cpp @@ -54,7 +54,7 @@ void AP_Proximity_SITL::update(void) if (AP::fence()->polyfence().inclusion_boundary_available()) { // update distance in one sector if (get_distance_to_fence(_sector_middle_deg[last_sector], _distance[last_sector])) { - set_status(AP_Proximity::Proximity_Good); + set_status(AP_Proximity::Status::Good); _distance_valid[last_sector] = true; _angle[last_sector] = _sector_middle_deg[last_sector]; update_boundary_for_sector(last_sector, true); @@ -66,7 +66,7 @@ void AP_Proximity_SITL::update(void) last_sector = 0; } } else { - set_status(AP_Proximity::Proximity_NoData); + set_status(AP_Proximity::Status::NoData); } } diff --git a/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.cpp b/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.cpp index 4b1dc9e806..bacf96a42b 100644 --- a/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.cpp +++ b/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.cpp @@ -60,9 +60,9 @@ void AP_Proximity_TeraRangerTower::update(void) // check for timeout and set health status if ((_last_distance_received_ms == 0) || (AP_HAL::millis() - _last_distance_received_ms > PROXIMITY_TRTOWER_TIMEOUT_MS)) { - set_status(AP_Proximity::Proximity_NoData); + set_status(AP_Proximity::Status::NoData); } else { - set_status(AP_Proximity::Proximity_Good); + set_status(AP_Proximity::Status::Good); } } diff --git a/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.cpp b/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.cpp index 5672f7bacc..011811da24 100644 --- a/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.cpp +++ b/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.cpp @@ -64,9 +64,9 @@ void AP_Proximity_TeraRangerTowerEvo::update(void) // check for timeout and set health status if ((_last_distance_received_ms == 0) || (AP_HAL::millis() - _last_distance_received_ms > PROXIMITY_TRTOWER_TIMEOUT_MS)) { - set_status(AP_Proximity::Proximity_NoData); + set_status(AP_Proximity::Status::NoData); } else { - set_status(AP_Proximity::Proximity_Good); + set_status(AP_Proximity::Status::Good); } }