AP_NavEKF3: make mag variance reporting consistent

logged scaled variance should match the value used in MAVLink
EKF_STATUS_REPORT
This commit is contained in:
Andrew Tridgell 2020-04-04 16:37:11 +11:00
parent 234ae5bc93
commit 4f7450dde9

View File

@ -598,10 +598,10 @@ void NavEKF3_core::send_status_report(mavlink_channel_t chan)
} else {
temp = 0.0f;
}
const float mag_max = fmaxf(fmaxf(magVar.x,magVar.y),magVar.z);
// send message
mavlink_msg_ekf_status_report_send(chan, flags, velVar, posVar, hgtVar, magVar.length(), temp, tasVar);
mavlink_msg_ekf_status_report_send(chan, flags, velVar, posVar, hgtVar, mag_max, temp, tasVar);
}
// report the reason for why the backend is refusing to initialise