mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_NavEKF3: Prevent on ground range to ground being used in flight
This commit is contained in:
parent
b0011ce014
commit
2eb627775a
@ -90,7 +90,7 @@ void NavEKF3_core::readRangeFinder(void)
|
|||||||
// indicate we have updated the measurement
|
// indicate we have updated the measurement
|
||||||
rngValidMeaTime_ms = imuSampleTime_ms;
|
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
|
// before takeoff we assume on-ground range value if there is no data
|
||||||
rangeDataNew.time_ms = imuSampleTime_ms;
|
rangeDataNew.time_ms = imuSampleTime_ms;
|
||||||
rangeDataNew.rng = rngOnGnd;
|
rangeDataNew.rng = rngOnGnd;
|
||||||
|
Loading…
Reference in New Issue
Block a user