mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_NavEKF3: use enum-class for RangeFinder Status
This commit is contained in:
parent
9735684184
commit
11b372a986
@ -41,7 +41,7 @@ void NavEKF3_core::readRangeFinder(void)
|
||||
if (sensor == nullptr) {
|
||||
continue;
|
||||
}
|
||||
if ((sensor->orientation() == ROTATION_PITCH_270) && (sensor->status() == RangeFinder::RangeFinder_Good)) {
|
||||
if ((sensor->orientation() == ROTATION_PITCH_270) && (sensor->status() == RangeFinder::Status::Good)) {
|
||||
rngMeasIndex[sensorIndex] ++;
|
||||
if (rngMeasIndex[sensorIndex] > 2) {
|
||||
rngMeasIndex[sensorIndex] = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user