AP_NavEKF3: clarify yaw reset error message

The current wording can be taken to indicate that the mag sensors
stopped, causing this issue.
This commit is contained in:
Peter Barker 2020-05-01 17:14:35 +10:00 committed by Andrew Tridgell
parent 6fa7dca68b
commit bf3cb977fd

View File

@ -1493,7 +1493,7 @@ bool NavEKF3_core::EKFGSF_resetMainFilterYaw()
if (effectiveMagCal == MagCal::GSF_YAW || AP::compass().get_num_enabled() == 0) {
gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u yaw aligned using GPS",(unsigned)imu_index);
} else {
gcs().send_text(MAV_SEVERITY_WARNING, "EKF3 IMU%u emergency yaw reset - mag sensor stopped",(unsigned)imu_index);
gcs().send_text(MAV_SEVERITY_WARNING, "EKF3 IMU%u emergency yaw reset",(unsigned)imu_index);
}
// Fail the magnetomer so it doesn't get used and pull the yaw away from the correct value