Browse Source

AP_RangeFinder: use enum-class for RangeFinder function

c415-sdk
Peter Barker 5 years ago committed by Peter Barker
parent
commit
1989decbc1
  1. 8
      libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp
  2. 8
      libraries/AP_RangeFinder/RangeFinder.h

8
libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp

@ -86,19 +86,19 @@ void AP_RangeFinder_analog::update(void) @@ -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 {

8
libraries/AP_RangeFinder/RangeFinder.h

@ -79,10 +79,10 @@ public: @@ -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 {

Loading…
Cancel
Save