From 1989decbc16a4ad5d67a0933bed710ec0241509b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 1 Nov 2019 14:06:21 +1100 Subject: [PATCH] AP_RangeFinder: use enum-class for RangeFinder function --- libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp | 8 ++++---- libraries/AP_RangeFinder/RangeFinder.h | 8 ++++---- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp index f1efea9fa1..f93e403b20 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp @@ -86,19 +86,19 @@ void AP_RangeFinder_analog::update(void) float dist_m = 0; float scaling = params.scaling; float offset = params.offset; - RangeFinder::RangeFinder_Function function = (RangeFinder::RangeFinder_Function)params.function.get(); + RangeFinder::Function function = (RangeFinder::Function)params.function.get(); int16_t _max_distance_cm = params.max_distance_cm; switch (function) { - case RangeFinder::FUNCTION_LINEAR: + case RangeFinder::Function::LINEAR: dist_m = (v - offset) * scaling; break; - case RangeFinder::FUNCTION_INVERTED: + case RangeFinder::Function::INVERTED: dist_m = (offset - v) * scaling; break; - case RangeFinder::FUNCTION_HYPERBOLA: + case RangeFinder::Function::HYPERBOLA: if (v <= offset) { dist_m = 0; } else { diff --git a/libraries/AP_RangeFinder/RangeFinder.h b/libraries/AP_RangeFinder/RangeFinder.h index fbec5656b5..97ea759dea 100644 --- a/libraries/AP_RangeFinder/RangeFinder.h +++ b/libraries/AP_RangeFinder/RangeFinder.h @@ -79,10 +79,10 @@ public: BenewakeTF03 = 27, }; - enum RangeFinder_Function { - FUNCTION_LINEAR = 0, - FUNCTION_INVERTED = 1, - FUNCTION_HYPERBOLA = 2 + enum class Function { + LINEAR = 0, + INVERTED = 1, + HYPERBOLA = 2 }; enum RangeFinder_Status {