mirror of
https://github.com/ArduPilot/ardupilot.git
synced 2026-02-07 07:55:39 +08:00
AP_HAL_Linux: fix checking wrong value for pthread function
Thanks to Phillip Khandeliants (@khandeliants) for reporting.
This commit is contained in:
@@ -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, ¶m) != 0)) {
|
||||
(r = pthread_attr_setschedparam(&attr, ¶m)) != 0) {
|
||||
AP_HAL::panic("Failed to set attributes for thread '%s': %s",
|
||||
name, strerror(r));
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user