mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_NavEKF2: Fix predicted nav reporting
Predicted nav should never be false if current nav is true
This commit is contained in:
parent
99f481e098
commit
ec5c460584
@ -473,8 +473,8 @@ void NavEKF2_core::getFilterStatus(nav_filter_status &status) const
|
||||
status.flags.vert_pos = !hgtTimeout && filterHealthy && !hgtNotAccurate; // vertical position estimate valid
|
||||
status.flags.terrain_alt = gndOffsetValid && filterHealthy; // terrain height estimate valid
|
||||
status.flags.const_pos_mode = (PV_AidingMode == AID_NONE) && filterHealthy; // constant position mode
|
||||
status.flags.pred_horiz_pos_rel = (optFlowNavPossible || gpsNavPossible) && filterHealthy; // we should be able to estimate a relative position when we enter flight mode
|
||||
status.flags.pred_horiz_pos_abs = gpsNavPossible && filterHealthy; // we should be able to estimate an absolute position when we enter flight mode
|
||||
status.flags.pred_horiz_pos_rel = ((optFlowNavPossible || gpsNavPossible) && filterHealthy) || status.flags.horiz_pos_rel; // we should be able to estimate a relative position when we enter flight mode
|
||||
status.flags.pred_horiz_pos_abs = (gpsNavPossible && filterHealthy) || status.flags.horiz_pos_abs; // we should be able to estimate an absolute position when we enter flight mode
|
||||
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
|
||||
|
Loading…
Reference in New Issue
Block a user