AP_NavEKF2: Fix reporting of terrain estimator innovations

Terrain height is relevant whenever optical flow data is present
This commit is contained in:
priseborough 2016-10-07 07:58:20 +11:00 committed by Randy Mackay
parent b0072b587c
commit 635826c056

View File

@ -520,10 +520,11 @@ void NavEKF2_core::send_status_report(mavlink_channel_t chan)
Vector2f offset;
getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset);
// Only report range finder normalised innovation levels if the EKF needs the data.
// This prevents false alarms at the GCS if a range finder is fitted for other applications
// Only report range finder normalised innovation levels if the EKF needs the data for primary
// height estimation or optical flow operation. This prevents false alarms at the GCS if a
// range finder is fitted for other applications
float temp;
if ((frontend->_useRngSwHgt > 0) || PV_AidingMode == AID_RELATIVE) {
if ((frontend->_useRngSwHgt > 0) || PV_AidingMode == AID_RELATIVE || flowDataValid) {
temp = sqrtf(auxRngTestRatio);
} else {
temp = 0.0f;