mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: Don't allow range finder use to start if terrain state is stale
This commit is contained in:
parent
b9863d8514
commit
2228937536
|
@ -1089,7 +1089,7 @@ void NavEKF3_core::selectHeightForFusion()
|
|||
// determine if we are above or below the height switch region
|
||||
ftype rangeMaxUse = 1e-4 * (ftype)_rng->max_distance_cm_orient(ROTATION_PITCH_270) * (ftype)frontend->_useRngSwHgt;
|
||||
bool aboveUpperSwHgt = (terrainState - stateStruct.position.z) > rangeMaxUse;
|
||||
bool belowLowerSwHgt = (terrainState - stateStruct.position.z) < 0.7f * rangeMaxUse;
|
||||
bool belowLowerSwHgt = ((terrainState - stateStruct.position.z) < 0.7f * rangeMaxUse) && (imuSampleTime_ms - gndHgtValidTime_ms < 1000);
|
||||
|
||||
// If the terrain height is consistent and we are moving slowly, then it can be
|
||||
// used as a height reference in combination with a range finder
|
||||
|
|
Loading…
Reference in New Issue