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:
parent
c9755cf9e6
commit
be674fc36c
@ -607,10 +607,10 @@ void NavEKF3_core::send_status_report(mavlink_channel_t chan) const
|
||||
} 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
|
||||
|
Loading…
Reference in New Issue
Block a user