|
|
|
@ -97,10 +97,11 @@ AP_DCM::matrix_update(float _G_Dt)
@@ -97,10 +97,11 @@ AP_DCM::matrix_update(float _G_Dt)
|
|
|
|
|
(fabs(_gyro_vector.z) >= radians(300))) |
|
|
|
|
gyro_sat_count++; |
|
|
|
|
|
|
|
|
|
if(_centrifugal){ |
|
|
|
|
_omega_integ_corr = _gyro_vector + _omega_I; // Used for centrep correction (theoretically better than _omega)
|
|
|
|
|
_omega = _omega_integ_corr + _omega_P; // Equation 16, adding proportional and integral correction terms
|
|
|
|
|
|
|
|
|
|
accel_adjust(); // Remove centrifugal acceleration.
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
#if OUTPUTMODE == 1 |
|
|
|
|
update_matrix.a.x = 0; |
|
|
|
@ -150,7 +151,16 @@ AP_DCM::accel_adjust(void)
@@ -150,7 +151,16 @@ AP_DCM::accel_adjust(void)
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
/**************************************************/ |
|
|
|
|
/*************************************************
|
|
|
|
|
Direction Cosine Matrix IMU: Theory |
|
|
|
|
William Premerlani and Paul Bizard |
|
|
|
|
|
|
|
|
|
Numerical errors will gradually reduce the orthogonality conditions expressed by equation 5
|
|
|
|
|
to approximations rather than identities. In effect, the axes in the two frames of reference no
|
|
|
|
|
longer describe a rigid body. Fortunately, numerical error accumulates very slowly, so it is a
|
|
|
|
|
simple matter to stay ahead of it. |
|
|
|
|
We call the process of enforcing the orthogonality conditions ÒrenormalizationÓ. |
|
|
|
|
*/ |
|
|
|
|
void
|
|
|
|
|
AP_DCM::normalize(void) |
|
|
|
|
{ |
|
|
|
|