This commit changes the way libraries headers are included in source files:
- If the header is in the same directory the source belongs to, so the
notation '#include ""' is used with the path relative to the directory
containing the source.
- If the header is outside the directory containing the source, then we use
the notation '#include <>' with the path relative to libraries folder.
Some of the advantages of such approach:
- Only one search path for libraries headers.
- OSs like Windows may have a better lookup time.
It's undefined behavior to pass the callback to pthread to a class
member like we were doing. Refactor the code so the callbacks are static
members.
This fixes the following warnings:
libraries/AP_HAL_Linux/Scheduler.cpp: In member function 'virtual void Linux::LinuxScheduler::init(void*)':
/home/lucas/p/dronecode/ardupilot/libraries/AP_HAL_Linux/Scheduler.cpp:61:76: warning: converting from 'void* (Linux::LinuxScheduler::*)()' to 'Linux::LinuxScheduler::pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
(pthread_startroutine_t)&Linux::LinuxScheduler::_timer_thread);
^
libraries/AP_HAL_Linux/Scheduler.cpp:65:76: warning: converting from 'void* (Linux::LinuxScheduler::*)()' to 'Linux::LinuxScheduler::pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
(pthread_startroutine_t)&Linux::LinuxScheduler::_uart_thread);
^
libraries/AP_HAL_Linux/Scheduler.cpp:69:76: warning: converting from 'void* (Linux::LinuxScheduler::*)()' to 'Linux::LinuxScheduler::pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
(pthread_startroutine_t)&Linux::LinuxScheduler::_rcin_thread);
^
libraries/AP_HAL_Linux/Scheduler.cpp:73:76: warning: converting from 'void* (Linux::LinuxScheduler::*)()' to 'Linux::LinuxScheduler::pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
(pthread_startroutine_t)&Linux::LinuxScheduler::_tonealarm_thread);
^
libraries/AP_HAL_Linux/Scheduler.cpp:77:76: warning: converting from 'void* (Linux::LinuxScheduler::*)()' to 'Linux::LinuxScheduler::pthread_startroutine_t {aka void* (*)(void*)}' [-Wpmf-conversions]
(pthread_startroutine_t)&Linux::LinuxScheduler::_io_thread);
LinuxScheduler::init() was not really working as it should. This was the
result of "ps -Leo class,rtprio,wchan,comm | grep ArduCopter":
FF 12 futex_ ArduCopter.elf
FF 12 usleep ArduCopter.elf
FF 12 hrtime ArduCopter.elf
FF 12 poll_s ArduCopter.elf
FF 12 hrtime ArduCopter.elf
FF 12 hrtime ArduCopter.elf
As can be seen all the threads run with the same priority, the one of the main
thread. There were basically 2 mistakes:
1) pthread_attr_setschedpolicy() needs to be called before
pthread_attr_setschedparam(). Otherwise the latter will just return
an error and not set the priority
2) pthread_create() defaults to ignore the priority and inherit the
it from the parent thread. pthread_attr_setinheritsched() needs to
be called to change the behavior to PTHREAD_EXPLICIT_SCHED. See
pthread_attr_setinheritsched(3) for an example program to test the
behaviors.
Also, it's undefined behavior to call pthread_attr_init() several times on the
same pthread_attr_t. Although we could reutilize the same attribute without
calling pthread_attr_init() again, lets refactor the code a little bit, so all
the pthread calls are in a single place. Then also call pthread_attr_destroy()
when we are done.