Browse Source

AP_NavEKF2: Fix bug in median filter code

master
priseborough 8 years ago committed by Randy Mackay
parent
commit
9779511425
  1. 4
      libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp

4
libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp

@ -60,8 +60,8 @@ void NavEKF2_core::readRangeFinder(void) @@ -60,8 +60,8 @@ void NavEKF2_core::readRangeFinder(void)
minIndex = 1;
maxIndex = 0;
} else {
maxIndex = 0;
minIndex = 1;
minIndex = 0;
maxIndex = 1;
}
if (storedRngMeas[sensorIndex][2] > storedRngMeas[sensorIndex][maxIndex]) {
midIndex = maxIndex;

Loading…
Cancel
Save