mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
HAL_PX4: fixed delay_microseconds() on PX4
we could underflow and delay a very long time!
This commit is contained in:
parent
9435eb4a15
commit
67db1cedaa
@ -90,8 +90,9 @@ void PX4Scheduler::delay_microseconds(uint16_t usec)
|
||||
}
|
||||
perf_begin(_perf_delay);
|
||||
uint32_t start = micros();
|
||||
while (micros() - start < usec) {
|
||||
up_udelay(usec - (micros() - start));
|
||||
uint32_t dt;
|
||||
while ((dt=(micros() - start)) < usec) {
|
||||
up_udelay(usec - dt);
|
||||
}
|
||||
perf_end(_perf_delay);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user