AP_NavEKF2: Fix bug in median filter code

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

View File

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