mirror of https://github.com/ArduPilot/ardupilot
HAL_SITL: allow delay() and delay_microseconds() to work in examples
when we have no sitl object we need to directly call stop_clock()
This commit is contained in:
parent
e4c103972c
commit
39efe75e79
|
@ -128,6 +128,11 @@ bool Scheduler::semaphore_wait_hack_required() const
|
|||
|
||||
void Scheduler::delay_microseconds(uint16_t usec)
|
||||
{
|
||||
if (_sitlState->_sitl == nullptr) {
|
||||
// this allows examples to run
|
||||
hal.scheduler->stop_clock(AP_HAL::micros64()+usec);
|
||||
return;
|
||||
}
|
||||
uint64_t start = AP_HAL::micros64();
|
||||
do {
|
||||
uint64_t dtime = AP_HAL::micros64() - start;
|
||||
|
|
Loading…
Reference in New Issue