// drift_correction_yaw - yaw drift correction using the compass
// we have no way to update the dmp with it's actual heading from our compass
// instead we use the yaw_corrected variable to hold what we think is the real heading
// we also record what the dmp said it's last heading was in the yaw_last_uncorrected variable so that on the next iteration we can add the change in yaw to our estimate
//
void
AP_AHRS_MPU6000::drift_correction_yaw(void)
{
staticfloatyaw_last_uncorrected=HEADING_UNKNOWN;
staticfloatyaw_corrected=HEADING_UNKNOWN;
floatyaw_delta=0;
boolnew_value=false;
floatyaw_error;
staticfloatlast_dmp_yaw=HEADING_UNKNOWN;
floatdmp_roll,dmp_pitch,dmp_yaw;// roll pitch and yaw values from dmp
floatyaw_delta;// change in yaw according to dmp
floatyaw_error;// difference between heading and corrected yaw
staticfloatheading;
// we assume the DCM matrix is completely uncorrect for yaw
// retrieve how much heading has changed according to non-corrected dcm
if(yaw_last_uncorrected!=HEADING_UNKNOWN){
yaw_delta=wrap_PI(yaw-yaw_last_uncorrected);// the change in heading according to the gyros only since the last interation