Skip to content

Commit

Permalink
AP_Schedule: fixed loop in example with sitl NULL
Browse files Browse the repository at this point in the history
  • Loading branch information
tridge committed Feb 23, 2024
1 parent c4df9ef commit c0914f4
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion libraries/AP_Scheduler/AP_Scheduler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down

0 comments on commit c0914f4

Please sign in to comment.