Browse Source

AP_NavEKF: change using_gps threshold to 4s

this means plane will continue to use dead reckoning with GPS 3D lock
for 4s
mission-4.1.18
Andrew Tridgell 10 years ago
parent
commit
92c4c5cbcf
  1. 2
      libraries/AP_NavEKF/AP_NavEKF.cpp

2
libraries/AP_NavEKF/AP_NavEKF.cpp

@ -4803,7 +4803,7 @@ void NavEKF::getFilterStatus(nav_filter_status &status) const @@ -4803,7 +4803,7 @@ void NavEKF::getFilterStatus(nav_filter_status &status) const
status.flags.takeoff_detected = takeOffDetected; // takeoff for optical flow navigation has been detected
status.flags.takeoff = expectGndEffectTakeoff; // The EKF has been told to expect takeoff and is in a ground effect mitigation mode
status.flags.touchdown = expectGndEffectTouchdown; // The EKF has been told to detect touchdown and is in a ground effect mitigation mode
status.flags.using_gps = (imuSampleTime_ms - lastPosPassTime) < 2000;
status.flags.using_gps = (imuSampleTime_ms - lastPosPassTime) < 4000;
}
// send an EKF_STATUS message to GCS

Loading…
Cancel
Save