AP_NavEKF2: Don't report range finder variance on mavlink if not required

This commit is contained in:
priseborough 2016-09-20 10:42:06 +10:00 committed by Randy Mackay
parent 95db9f61cc
commit b6867e085d

View File

@ -520,8 +520,17 @@ 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
float temp;
if ((frontend->_useRngSwHgt > 0) || PV_AidingMode == AID_RELATIVE) {
temp = sqrtf(auxRngTestRatio);
} else {
temp = 0.0f;
}
// send message
mavlink_msg_ekf_status_report_send(chan, flags, velVar, posVar, hgtVar, magVar.length(), sqrtf(auxRngTestRatio));
mavlink_msg_ekf_status_report_send(chan, flags, velVar, posVar, hgtVar, magVar.length(), temp);
}