diff --git a/ArduSub/commands_logic.cpp b/ArduSub/commands_logic.cpp index f35eac7967..681022a3dd 100644 --- a/ArduSub/commands_logic.cpp +++ b/ArduSub/commands_logic.cpp @@ -401,7 +401,11 @@ void Sub::do_nav_delay(const AP_Mission::Mission_Command& cmd) nav_delay_time_max_ms = cmd.content.nav_delay.seconds * 1000; // convert seconds to milliseconds } else { // absolute delay to utc time +#if AP_RTC_ENABLED 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); +#else + nav_delay_time_max_ms = 0; +#endif } gcs().send_text(MAV_SEVERITY_INFO, "Delaying %u sec", (unsigned)(nav_delay_time_max_ms/1000)); }