diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index 41bee9a24c..7e9aaa2303 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -1369,7 +1369,7 @@ void ModeAuto::do_nav_delay(const AP_Mission::Mission_Command& cmd) // absolute delay to utc time nav_delay_time_max_ms = AP::rtc().get_time_utc(cmd.content.nav_delay.hour_utc, cmd.content.nav_delay.min_utc, cmd.content.nav_delay.sec_utc, 0); } - gcs().send_text(MAV_SEVERITY_INFO, "Delaying %u sec",nav_delay_time_max_ms/1000); + gcs().send_text(MAV_SEVERITY_INFO, "Delaying %u sec", (unsigned)(nav_delay_time_max_ms/1000)); } /********************************************************************************/