AP_NavEKF: Fix bug in median filter code

This commit is contained in:
priseborough 2016-10-19 21:32:28 +11:00 committed by Randy Mackay
parent 83b8208b8b
commit d0ba259d0d

View File

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