mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_NavEKF : Inhibit flow and range fusion in static mode
This commit is contained in:
parent
9b9934ac06
commit
839b814d12
@ -929,7 +929,7 @@ void NavEKF::SelectFlowFusion()
|
||||
// check if fusion should be delayed to spread load. Setting fuseMeNow to true disables this load spreading feature.
|
||||
bool delayFusion = ((covPredStep || magFusePerformed) && !(timeout || inhibitLoadLeveling));
|
||||
// if the filter is initialised, we have data to fuse and the vehicle is not excessively tilted, then perform optical flow fusion
|
||||
if (useOptFlow() && newDataFlow && tiltOK && !delayFusion)
|
||||
if (useOptFlow() && newDataFlow && tiltOK && !delayFusion && !staticMode)
|
||||
{
|
||||
// Set the flow noise used by the fusion processes
|
||||
R_LOS = sq(max(_flowNoise, 0.05f));
|
||||
|
Loading…
Reference in New Issue
Block a user