HAL_PX4: use pthread_yield() in main loop
this lowers the latency of the main loop somewhat
This commit is contained in:
parent
6e8501603c
commit
06e63d3167
@ -11,7 +11,6 @@
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
#include <nuttx/analog/adc.h>
|
||||
#include <poll.h>
|
||||
|
||||
#define ANLOGIN_DEBUGGING 0
|
||||
|
||||
|
@ -20,11 +20,11 @@
|
||||
#include <AP_HAL_Empty_Private.h>
|
||||
|
||||
#include <stdlib.h>
|
||||
#include <poll.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <nuttx/config.h>
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <pthread.h>
|
||||
|
||||
using namespace PX4;
|
||||
|
||||
@ -90,10 +90,9 @@ static int main_loop(int argc, char **argv)
|
||||
thread_running = true;
|
||||
while (!_px4_thread_should_exit) {
|
||||
loop();
|
||||
|
||||
// yield the CPU for 1ms between loops to let other apps
|
||||
// yield the CPU between loops to let other apps
|
||||
// get some CPU time
|
||||
poll(NULL, 0, 1);
|
||||
pthread_yield();
|
||||
}
|
||||
thread_running = false;
|
||||
return 0;
|
||||
|
Loading…
Reference in New Issue
Block a user