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