mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Schedule: fixed loop in example with sitl NULL
This commit is contained in:
parent
66ff84e6fb
commit
7226c5107d
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user