mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_NavEKF2: Fix bug in median filter code
This commit is contained in:
parent
d0ba259d0d
commit
9779511425
@ -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;
|
||||||
|
Loading…
Reference in New Issue
Block a user