this uses a new formulation of the GPS based drift correction from
Bill Premerlani that rotates the error vector to avoid relying on
accurate yaw. This means we should get accurate roll/pitch correction
even with lots of magnetometer interference
It also makes it possible to fly a multicopter with no compass. It can
even navigate and correct yaw (slowly!)
this seems to have been the cause of the 'flips' seen by Marco and
others. Testing by Craig and Alan shows that the flips are gone when
the barometric acceleration is removed.
It looks like a 5 point average filter is not enough to keep the
vertical acceleteration noise low. With high noise in the z axes, the
x and y axes are scaled back when the ge vector is normalised.
this follows the method that Bill developed in his fastRotations
paper. We've demonstrated that this is indeed needed in APM, as we
were able to produce the 'dizzy' effects in both the ArduPlane and
ArduCopter simulator
omega_I applied continuously. _ki larger. Stop integrating when _omega.length()>20
The key change was the scaling of ge to ensure the error is not
quadratic
This makes 3 major changes:
1) fixes the scaling of the yaw drift correction term to fix the time
constant
2) don't integrate the mag vector over multiple readings
3) accumulate omega_I changes over 15 seconds before applying, to try
to prevent omega_I picking up short term responses
When using GPS for yaw correction we need to apply the x and y omegaI
corrections from the _omega_I_sum in the period before we get to the
minimum ground speed for GPS yaw correction. Otherwise we get a large
sudden omega_I change on takeoff.
this buffers up _omega_I changes in _omega_I_sum over a period of 10
seconds, applying the slope limit only when _omega_I_sum is
transferred to _omega_I.
The result is a huge improvement in the ability of _omega_I to track
gyro drift over the long term.
the 'drop z' method reduced the impact of noise on omegaI, but it also
made us more sensitive to errors in accelerometer calibration and
scaling, as demonstated by the logs from Gabor here:
http://diydrones.com/xn/detail/705844:Comment:834373
Simulation testing shows that the other noise suppression methods
applied in the DCM code, in particular the slope limiting on omegaI
the removal of the weighting and the upcoming use of a _omega_I_sum
buffer have reduced the impact of noise enough that we can now safely
include z in the acceleration calculation.
when a user first connects with USB, and later switches to the
telemetry port without restarting we were getting zero for error_yaw
in the logs, as AHRS.get_error_yaw() was being called twice.
This ensures we give the last value after the counter is reset