mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
HAL_Linux: fixed timer scheduler
This commit is contained in:
parent
88959004d7
commit
f03315237a
@ -104,9 +104,6 @@ uint8_t LinuxI2CDriver::read(uint8_t addr, uint8_t len, uint8_t* data)
|
|||||||
if (!set_address(addr)) {
|
if (!set_address(addr)) {
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
if (write(addr, 0, NULL) != 0) {
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
if (::read(_fd, data, len) != len) {
|
if (::read(_fd, data, len) != len) {
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
@ -27,6 +27,7 @@ void LinuxScheduler::init(void* machtnichts)
|
|||||||
struct sched_param param;
|
struct sched_param param;
|
||||||
|
|
||||||
param.sched_priority = APM_LINUX_TIMER_PRIORITY;
|
param.sched_priority = APM_LINUX_TIMER_PRIORITY;
|
||||||
|
pthread_attr_init(&thread_attr);
|
||||||
(void)pthread_attr_setschedparam(&thread_attr, ¶m);
|
(void)pthread_attr_setschedparam(&thread_attr, ¶m);
|
||||||
pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
|
pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user