Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

HAL_Linux: reduce delay(ms) jitter #26195

Merged
merged 1 commit into from Feb 25, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
13 changes: 9 additions & 4 deletions libraries/AP_HAL_Linux/Scheduler.cpp
Expand Up @@ -173,15 +173,20 @@ void Scheduler::delay(uint16_t ms)
return;
}

uint64_t start = AP_HAL::millis64();
if (ms == 0) {
return;
}

while ((AP_HAL::millis64() - start) < ms) {
uint64_t now = AP_HAL::micros64();
uint64_t end = now + 1000UL * ms + 1U;
do {
// this yields the CPU to other apps
microsleep(1000);
microsleep(MIN(1000UL, end-now));
if (in_main_thread() && _min_delay_cb_ms <= ms) {
call_delay_cb();
}
}
now = AP_HAL::micros64();
} while (now < end);
}

void Scheduler::delay_microseconds(uint16_t us)
Expand Down