mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: make mag variance reporting consistent
logged scaled variance should match the value used in MAVLink EKF_STATUS_REPORT
This commit is contained in:
parent
2ed550966d
commit
c9755cf9e6
|
@ -587,6 +587,8 @@ void NavEKF2_core::send_status_report(mavlink_channel_t chan) const
|
|||
Vector2f offset;
|
||||
getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset);
|
||||
|
||||
const float mag_max = fmaxf(fmaxf(magVar.x,magVar.y),magVar.z);
|
||||
|
||||
// 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
|
||||
|
@ -598,7 +600,7 @@ void NavEKF2_core::send_status_report(mavlink_channel_t chan) const
|
|||
}
|
||||
|
||||
// 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