diff --git a/libraries/AP_Scheduler/AP_Scheduler.cpp b/libraries/AP_Scheduler/AP_Scheduler.cpp
index 5fd91703b114b..62a702bb86b19 100644
--- a/libraries/AP_Scheduler/AP_Scheduler.cpp
+++ b/libraries/AP_Scheduler/AP_Scheduler.cpp
@@ -360,7 +360,7 @@ void AP_Scheduler::loop()
           for testing low CPU conditions we can add an optional delay in SITL
         */
         auto *sitl = AP::sitl();
-        uint32_t loop_delay_us = sitl->loop_delay.get();
+        uint32_t loop_delay_us = sitl? sitl->loop_delay.get() : 1000U;
         hal.scheduler->delay_microseconds(loop_delay_us);
     }
 #endif