AP_HAL_Linux: fix checking wrong value for pthread function

Thanks to Phillip Khandeliants (@khandeliants) for reporting.
This commit is contained in:
Lucas De Marchi 2017-04-18 15:04:27 -07:00
parent 9324d8e251
commit 6f952fe3dd
1 changed files with 1 additions and 1 deletions

View File

@ -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));
}