mirror of https://github.com/ArduPilot/ardupilot
AP_OSD: fixed CPU usage in SITL thread
This commit is contained in:
parent
b5b9ff8dbc
commit
ba1a611ea9
|
@ -137,6 +137,7 @@ void AP_OSD_SITL::update_thread(void)
|
|||
w->close();
|
||||
}
|
||||
if (counter == last_counter) {
|
||||
usleep(10000);
|
||||
continue;
|
||||
}
|
||||
last_counter = counter;
|
||||
|
|
Loading…
Reference in New Issue