Browse Source

AP_HAL_Linux: fix checking wrong value for pthread function

Thanks to Phillip Khandeliants (@khandeliants) for reporting.
mission-4.1.18
Lucas De Marchi 8 years ago
parent
commit
6f952fe3dd
  1. 2
      libraries/AP_HAL_Linux/Thread.cpp

2
libraries/AP_HAL_Linux/Thread.cpp

@ -172,7 +172,7 @@ bool Thread::start(const char *name, int policy, int prio) @@ -172,7 +172,7 @@ bool Thread::start(const char *name, int policy, int prio)
if (geteuid() == 0) {
if ((r = pthread_attr_setinheritsched(&attr, PTHREAD_EXPLICIT_SCHED)) != 0 ||
(r = pthread_attr_setschedpolicy(&attr, policy)) != 0 ||
(r = pthread_attr_setschedparam(&attr, &param) != 0)) {
(r = pthread_attr_setschedparam(&attr, &param)) != 0) {
AP_HAL::panic("Failed to set attributes for thread '%s': %s",
name, strerror(r));
}

Loading…
Cancel
Save