The main thread would always be blocked on the semaphore to read the
data from accelerometer and gyroscope. Especially if we have a slow
update of these values in _accumulate() due to the I2C transfer function
taking too much time: the timer thread would never give up the CPU,
causing starvation on the main thread.
This fixes the issue by reducing the critical region using a flip-buffer
so _accumulate() can work on its own copy of the data. Now that the
critical region is smaller, also avoid the semaphore and use a spinlock
instead.
All threads share the same address space and have the same pages locked
into memory so it's not necessary to call mlockall() for each of them.
Grepping /proc/<tid>/status gives the same VmLck for all of them, even
when only the main thread locks the memory:
# for i in `seq 477 482`; do \
name=$(cat /proc/$i/comm); \
vm=$(cat /proc/$i/status |grep VmLck); \
echo -e "$name\t$vm"; \
done
ArduCopter.elf VmLck: 57868 kB
sched-timer VmLck: 57868 kB
sched-uart VmLck: 57868 kB
sched-rcin VmLck: 57868 kB
sched-tonealarm VmLck: 57868 kB
sched-io VmLck: 57868 kB
Use pthread_setname_np() to set thread name so it's easier to debug
what't going on with each of them. This is the example output of the
relevant par of "ps -Leo class,rtprio,wchan,comm":
FF 12 futex_ ArduCopter.elf
FF 15 usleep sched-timer
FF 14 hrtime sched-uart
FF 13 poll_s sched-rcin
FF 11 hrtime sched-tonealarm
FF 10 hrtime sched-io
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.
In Linux the default stack size is always greater than 32k, either 2MB
or 8MB depending on the architecture. There's no point in creating a
function to lock 32k.
Falls back to baro if range finder is unavailable
Adds parameter enabling user to select which height source (baro or range finder) will be used during optical flow nav.
In AP_MotorsTri.cpp the AP_MOTORS_MOT_1, _2 and _4 constants are
always mapped to actual output channels through _motor_to_channel_map
while the _CH_TRI_YAW is not, but there were a few inconsistencies
in this that could lead to things like PWM min and max values being
set on wrong channels.
It looks like all in all _motor_to_channel_map being in PROGMEM
probably doesn't help save memory and I'm not sure how useful it is
in the first place but regardless the usage should be consistent.
When performing a u-turn in AUTO (waypoints are 180deg turn from each other) sometimes the aircraft can't decide to turn left or right and wobbled back and forth a couple times. There was existing code to solve this but it was not executing all the time like when in LOITER mode. Frankly, I don't understand the criteria that was required to make it execute and i suspect there is still a gremlin in that logic but just executing the check all the time makes prevents the wobble behavior.
this allows a HAL_PARAM_DEFAULTS_PATH to be specified for a build to
override the default parameters for a build. This is useful to build a
firmware that has different default parameters
The magnetic field states are reset once at 1.5 metres and again at 5 metres. This height check was using the height at the first arm event as the reference. In the situation where there is baro drift and extgended time between the first arm event and flight, this can cause the magnetic field state to be reset when on the ground. If this happens when flying off a metallic surface, the resultant heading errors can cause sever toilet bowling.
Improve the quality of the GPS required to set an EKF origin
Eliminate repeated update of origin height - origin height updates once when EKF origin is set.
Operation in GPS mode is linked to setting of origin
The maximum time copters can reject GPS has been reduced from 10 to 7 seconds as flight logs have show that inertial dead reckoning with vibration and calibration errors is not good enough to support 10 seconds without aiding.
This patch causes the EKF to update the height of its origin each time it receives a valid GPs message whislt disarmed.
The resultant EKF origin height represents the height of the zero baro alt datum relative to the GPS height datum.
Flight tests have shown that the magnetic field distortion associated with flight from steel structures can extend 3m or higher. To counteract this, a second and final yaw and magnetic field alignment has been added which is activated when the height exceeds 5m for the first time.
Logic used to delay optical flow and airspeed fusion to prevent it occurring on the same time step as magnetometer fusion has been removed. This is no longer required to efficiency improvements made at the firmware level.
Improvements in PX4 firmware have reduced the computational load and mkae the previous practicwe of splitting magnetometer and optical flow fusion across multiple time steps unnecessary and make it possible to perform a covariance prediction prior to fusing data on the same time step. This patch:
1) Ensures that a covariance prediction is always performed prior to fusion of any observation
2) Removes the splitting of magnetometer fusion so that fusion of the X,Y and Z components occurs on the same time time step
3) Removes the splitting of optical flow fusion so that fusion of X and Y components occurs on the same time step
UBlox receivers report an estimate of the speed accuracy that tests show correlates well to speed glitches. Using this to scale the GPS velocity observation noise will reduce the effect of bad GPS velocity data.
we must not update _gyro_offset[] until we have completed calibration
of that gyro, or we will end up using the new offsets when asking for
the raw gyro vector
this moves the pitch constraint smoothly between unconstrained and
fully constrained over two time constants before the flare. This
greatly reduces the sudden pitch changes at flare
_copy_to_frontend function takes care of abstracting
this code from the driver. For now the function takes
care of the offset and rotation that is common.