mirror of https://github.com/ArduPilot/ardupilot
HAL_Linux: tweak the scheduling priorities
This commit is contained in:
parent
d3fe625742
commit
a1ef1a9318
|
@ -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(¶m, 0, sizeof(param));
|
||||
|
||||
param.sched_priority = APM_LINUX_MAIN_PRIORITY;
|
||||
sched_setscheduler(0, SCHED_FIFO, ¶m);
|
||||
|
||||
param.sched_priority = APM_LINUX_TIMER_PRIORITY;
|
||||
pthread_attr_init(&thread_attr);
|
||||
(void)pthread_attr_setschedparam(&thread_attr, ¶m);
|
||||
|
|
|
@ -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();
|
||||
|
|
Loading…
Reference in New Issue