Browse Source

Copter: delete \n from the log using gcs().send_text

master
murata 7 years ago committed by Randy Mackay
parent
commit
c13d6580ae
  1. 2
      ArduCopter/ekf_check.cpp

2
ArduCopter/ekf_check.cpp

@ -209,7 +209,7 @@ void Copter::check_ekf_reset() @@ -209,7 +209,7 @@ void Copter::check_ekf_reset()
if ((EKF2.getPrimaryCoreIndex() != ekf_primary_core) && (EKF2.getPrimaryCoreIndex() != -1)) {
ekf_primary_core = EKF2.getPrimaryCoreIndex();
Log_Write_Error(ERROR_SUBSYSTEM_EKF_PRIMARY, ekf_primary_core);
gcs().send_text(MAV_SEVERITY_WARNING, "EKF primary changed:%d\n", (unsigned)ekf_primary_core);
gcs().send_text(MAV_SEVERITY_WARNING, "EKF primary changed:%d", (unsigned)ekf_primary_core);
}
#endif
}

Loading…
Cancel
Save