From c0914f416f4be12d10d447f863d64dcd9d487454 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 23 Feb 2024 11:59:42 +1100 Subject: [PATCH] AP_Schedule: fixed loop in example with sitl NULL --- libraries/AP_Scheduler/AP_Scheduler.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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