mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF : Fix bug affecting sonar fusion
This commit is contained in:
parent
117bd2a998
commit
1222559da0
|
@ -3996,6 +3996,7 @@ void NavEKF::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, V
|
||||||
}
|
}
|
||||||
// Use range finder if 3 or more consecutive good samples. This reduces likelihood of using bad data.
|
// Use range finder if 3 or more consecutive good samples. This reduces likelihood of using bad data.
|
||||||
if (rangeHealth >= 3) {
|
if (rangeHealth >= 3) {
|
||||||
|
statesAtRngTime = statesAtFlowTime;
|
||||||
rngMea = rawSonarRange;
|
rngMea = rawSonarRange;
|
||||||
newDataRng = true;
|
newDataRng = true;
|
||||||
} else {
|
} else {
|
||||||
|
|
Loading…
Reference in New Issue