mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_NavEKF3: Fix solution validity reporting bug
Fixes bug that causes relative position status to report as false when using optical flow and using range finder as the primary height sensor.
This commit is contained in:
parent
082f429da3
commit
1301b9797a
@ -40,8 +40,8 @@ void NavEKF3_core::SelectFlowFusion()
|
||||
// Perform Data Checks
|
||||
// Check if the optical flow data is still valid
|
||||
flowDataValid = ((imuSampleTime_ms - flowValidMeaTime_ms) < 1000);
|
||||
// check is the terrain offset estimate is still valid
|
||||
gndOffsetValid = ((imuSampleTime_ms - gndHgtValidTime_ms) < 5000);
|
||||
// check is the terrain offset estimate is still valid - if we are using range finder as the main height reference, the ground is assumed to be at 0
|
||||
gndOffsetValid = ((imuSampleTime_ms - gndHgtValidTime_ms) < 5000) || (activeHgtSource == HGT_SOURCE_RNG);
|
||||
// Perform tilt check
|
||||
bool tiltOK = (prevTnb.c.z > frontend->DCM33FlowMin);
|
||||
// Constrain measurements to zero if takeoff is not detected and the height above ground
|
||||
|
Loading…
Reference in New Issue
Block a user