AP_NavEKF3: Fix yaw sensor alignment status reporting

This commit is contained in:
priseborough 2017-07-20 08:53:29 +10:00 committed by Andrew Tridgell
parent 977a7b68ed
commit 71d358803a
1 changed files with 1 additions and 1 deletions

View File

@ -233,7 +233,7 @@ void NavEKF3_core::alignYawAngle()
initialiseQuatCovariances(angleErrVarVec);
// send yaw alignment information to console
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "EKF3 IMU%u yaw aligned",(unsigned)imu_index);
gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u yaw aligned",(unsigned)imu_index);
// record the yaw reset event