AP_NavEKF3: delete \n from the log using gcs().send_text
This commit is contained in:
parent
184b017b33
commit
aef9fa4a63
@ -391,7 +391,7 @@ void NavEKF3_core::checkAttitudeAlignmentStatus()
|
||||
Vector3f angleErrVarVec = calcRotVecVariances();
|
||||
if ((angleErrVarVec.x + angleErrVarVec.y) < sq(0.05235f)) {
|
||||
tiltAlignComplete = true;
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u tilt alignment complete\n",(unsigned)imu_index);
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u tilt alignment complete",(unsigned)imu_index);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -119,14 +119,14 @@ void NavEKF3_core::controlMagYawReset()
|
||||
|
||||
// send initial alignment status to console
|
||||
if (!yawAlignComplete) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u initial yaw alignment complete\n",(unsigned)imu_index);
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u initial yaw alignment complete",(unsigned)imu_index);
|
||||
}
|
||||
|
||||
// send in-flight yaw alignment status to console
|
||||
if (finalResetRequest) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u in-flight yaw alignment complete\n",(unsigned)imu_index);
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u in-flight yaw alignment complete",(unsigned)imu_index);
|
||||
} else if (interimResetRequest) {
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "EKF3 IMU%u ground mag anomaly, yaw re-aligned\n",(unsigned)imu_index);
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "EKF3 IMU%u ground mag anomaly, yaw re-aligned",(unsigned)imu_index);
|
||||
}
|
||||
|
||||
// update the yaw reset completed status
|
||||
|
Loading…
Reference in New Issue
Block a user