Browse Source

AP_NavEKF3: Fix yaw sensor alignment status reporting

master
priseborough 8 years ago committed by Andrew Tridgell
parent
commit
71d358803a
  1. 2
      libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp

2
libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp

@ -233,7 +233,7 @@ void NavEKF3_core::alignYawAngle() @@ -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

Loading…
Cancel
Save