Browse Source

AP_NavEKF: Fix bug in median filter code

master
priseborough 8 years ago committed by Randy Mackay
parent
commit
d0ba259d0d
  1. 4
      libraries/AP_NavEKF/AP_NavEKF_core.cpp

4
libraries/AP_NavEKF/AP_NavEKF_core.cpp

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

Loading…
Cancel
Save