HAL_Linux: tweak the scheduling priorities

This commit is contained in:
Andrew Tridgell 2013-09-29 10:16:07 +10:00
parent d3fe625742
commit a1ef1a9318
2 changed files with 10 additions and 5 deletions

View File

@ -15,6 +15,11 @@ using namespace Linux;
extern const AP_HAL::HAL& hal;
#define APM_LINUX_MAIN_PRIORITY 180
#define APM_LINUX_TIMER_PRIORITY 182
#define APM_LINUX_UART_PRIORITY 181
#define APM_LINUX_IO_PRIORITY 59
LinuxScheduler::LinuxScheduler()
{}
@ -27,6 +32,11 @@ void LinuxScheduler::init(void* machtnichts)
pthread_attr_t thread_attr;
struct sched_param param;
memset(&param, 0, sizeof(param));
param.sched_priority = APM_LINUX_MAIN_PRIORITY;
sched_setscheduler(0, SCHED_FIFO, &param);
param.sched_priority = APM_LINUX_TIMER_PRIORITY;
pthread_attr_init(&thread_attr);
(void)pthread_attr_setschedparam(&thread_attr, &param);

View File

@ -10,11 +10,6 @@
#define LINUX_SCHEDULER_MAX_TIMER_PROCS 10
#define APM_LINUX_MAIN_PRIORITY 180
#define APM_LINUX_TIMER_PRIORITY 181
#define APM_LINUX_UART_PRIORITY 60
#define APM_LINUX_IO_PRIORITY 59
class Linux::LinuxScheduler : public AP_HAL::Scheduler {
public:
LinuxScheduler();