mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: Prevent on ground range to ground being used in flight
This commit is contained in:
parent
74ff64f440
commit
ab8c30a282
|
@ -90,7 +90,7 @@ void NavEKF3_core::readRangeFinder(void)
|
|||
// indicate we have updated the measurement
|
||||
rngValidMeaTime_ms = imuSampleTime_ms;
|
||||
|
||||
} else if (!takeOffDetected && ((imuSampleTime_ms - rngValidMeaTime_ms) > 200)) {
|
||||
} else if (onGround && ((imuSampleTime_ms - rngValidMeaTime_ms) > 200)) {
|
||||
// before takeoff we assume on-ground range value if there is no data
|
||||
rangeDataNew.time_ms = imuSampleTime_ms;
|
||||
rangeDataNew.rng = rngOnGnd;
|
||||
|
|
Loading…
Reference in New Issue