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
531cf5f3fb
commit
6e5f61935c
@ -578,6 +578,8 @@ void NavEKF2_core::send_status_report(mavlink_channel_t chan)
|
||||
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
|
||||
@ -589,7 +591,7 @@ void NavEKF2_core::send_status_report(mavlink_channel_t chan)
|
||||
}
|
||||
|
||||
// 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