This is a port from the library for Arduino provided by Sparkfun with their breakout board of the LSM9DS0. The original library can be found here: https://github.com/sparkfun/SparkFun_LSM9DS0_Arduino_Library/tree/V_1.0.1 It is also provided an AHRS example based on Madgwick, also a port from an Arduino example. All of this was tested on a Nucleo F411RE and a Sparkfun breakout board.

Dependencies:   mbed

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers AHRS_example.cpp Source File

AHRS_example.cpp

00001 #include "LSM9DS0_mbed.h"
00002 #include "mbed.h"
00003 
00004 #define INT1    PB_3
00005 #define INT2    PA_10
00006 #define DR_DYG  PB_5
00007 
00008 #define SDA PB_9
00009 #define SCL PB_8
00010 
00011 ///////////////////////
00012 // Example I2C Setup //
00013 ///////////////////////
00014 // SDO_XM and SDO_G are both grounded, so our addresses are:
00015 #define LSM9DS0_XM  0x1D // Would be 0x1E if SDO_XM is LOW
00016 #define LSM9DS0_G   0x6B // Would be 0x6A if SDO_G is LOW
00017 
00018 // Create an instance of the LSM9DS0 library called `dof` the
00019 // parameters for this constructor are:
00020 // [I2C SDA], [I2C SCL],[gyro I2C address],[xm I2C add.]
00021 LSM9DS0 dof(SDA, SCL, LSM9DS0_G, LSM9DS0_XM);
00022 
00023 ///////////////////////////////////
00024 // Interrupt Handler Definitions //
00025 ///////////////////////////////////
00026 DigitalIn INT1XM(INT1);
00027 DigitalIn INT2XM(INT2);
00028 DigitalIn DRDYG(DR_DYG);
00029 
00030 // global constants for 9 DoF fusion and AHRS (Attitude and Heading Reference System)
00031 #define GyroMeasError PI * (40.0f / 180.0f)       // gyroscope measurement error in rads/s (shown as 3 deg/s)
00032 #define GyroMeasDrift PI * (0.0f / 180.0f)      // gyroscope measurement drift in rad/s/s (shown as 0.0 deg/s/s)
00033 // There is a tradeoff in the beta parameter between accuracy and response speed.
00034 // In the original Madgwick study, beta of 0.041 (corresponding to GyroMeasError of 2.7 degrees/s) was found to give optimal accuracy.
00035 // However, with this value, the LSM9SD0 response time is about 10 seconds to a stable initial quaternion.
00036 // Subsequent changes also require a longish lag time to a stable output, not fast enough for a quadcopter or robot car!
00037 // By increasing beta (GyroMeasError) by about a factor of fifteen, the response time constant is reduced to ~2 sec
00038 // I haven't noticed any reduction in solution accuracy. This is essentially the I coefficient in a PID control sense;
00039 // the bigger the feedback coefficient, the faster the solution converges, usually at the expense of accuracy.
00040 // In any case, this is the free parameter in the Madgwick filtering and fusion scheme.
00041 #define beta sqrt(3.0f / 4.0f) * GyroMeasError   // compute beta
00042 #define zeta sqrt(3.0f / 4.0f) * GyroMeasDrift   // compute zeta, the other free parameter in the Madgwick scheme usually set to a small or zero value
00043 #define Kp 2.0f * 5.0f // these are the free parameters in the Mahony filter and fusion scheme, Kp for proportional feedback, Ki for integral
00044 #define Ki 0.0f
00045 const float  PI = 3.14159265358979f;
00046 
00047 Timer t1;   //Integration timer
00048 Timer t2;   //Print timer
00049 Serial pc(SERIAL_TX, SERIAL_RX);
00050 DigitalOut myled(LED1);
00051 float pitch, yaw, roll, heading;
00052 float deltat = 0.0f;        // integration interval for both filter schemes
00053 
00054 
00055 float abias[3] = {0, 0, 0}, gbias[3] = {0, 0, 0};
00056 float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values
00057 float q[4] = {1.0f, 0.0f, 0.0f, 0.0f};    // vector to hold quaternion
00058 float eInt[3] = {0.0f, 0.0f, 0.0f};       // vector to hold integral error for Mahony method
00059 float temperature;
00060 
00061 //////////////////////////////////
00062 //      FUNCTION DECLARATION    //
00063 //////////////////////////////////
00064 void setup();
00065 void loop();
00066 void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz);
00067 void MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz);
00068 void dataGyro();
00069 void dataAccel();
00070 void dataMag();
00071 
00072 //////////////////////////////////
00073 //             MAIN             //
00074 //////////////////////////////////
00075 int main()
00076 {
00077     setup();  //Setup sensor and Serial
00078     pc.printf("Setup Done\n\r");
00079 
00080 
00081     while (true)
00082         loop();
00083 }
00084 
00085 
00086 //////////////////////////////////
00087 //          FUNCTION BODY       //
00088 //////////////////////////////////
00089 void dataGyro()
00090 {
00091     dof.readGyro();           // Read raw gyro data
00092     gx = dof.calcGyro(dof.gx) - gbias[0];   // Convert to degrees per seconds, remove gyro biases
00093     gy = dof.calcGyro(dof.gy) - gbias[1];
00094     gz = dof.calcGyro(dof.gz) - gbias[2];
00095 }
00096 void dataAccel()
00097 {
00098     dof.readAccel();         // Read raw accelerometer data
00099     ax = dof.calcAccel(dof.ax) - abias[0];   // Convert to g's, remove accelerometer biases
00100     ay = dof.calcAccel(dof.ay) - abias[1];
00101     az = dof.calcAccel(dof.az) - abias[2];
00102 }
00103 void dataMag()
00104 {
00105     dof.readMag();           // Read raw magnetometer data
00106     mx = dof.calcMag(dof.mx);     // Convert to Gauss and correct for calibration
00107     my = dof.calcMag(dof.my);
00108     mz = dof.calcMag(dof.mz);
00109 }
00110 void setup()
00111 {
00112     pc.baud(115200); // Start serial at 115200 bps
00113     myled = true;
00114     /*//Interrupt
00115     INT1XM.rise(&dataAccel);
00116     INT2XM.rise(&dataMag);
00117     DRDYG.rise(&dataGyro);
00118     */
00119     // begin() returns a 16-bit value which includes both the gyro
00120     // and accelerometers WHO_AM_I response. You can check this to
00121     // make sure communication was successful.
00122     uint16_t status = dof.begin();
00123 
00124     pc.printf("LSM9DS0 WHO_AM_I's returned: ");
00125     pc.printf("0x%X\t", status);
00126     pc.printf("Should be 0x49D4");
00127     pc.printf("\n\r");
00128 
00129 
00130 // Set data output ranges; choose lowest ranges for maximum resolution
00131 // Accelerometer scale can be: A_SCALE_2G, A_SCALE_4G, A_SCALE_6G, A_SCALE_8G, or A_SCALE_16G
00132     dof.setAccelScale(dof.A_SCALE_2G);
00133 // Gyro scale can be:  G_SCALE__245, G_SCALE__500, or G_SCALE__2000DPS
00134     dof.setGyroScale(dof.G_SCALE_245DPS);
00135 // Magnetometer scale can be: M_SCALE_2GS, M_SCALE_4GS, M_SCALE_8GS, M_SCALE_12GS
00136     dof.setMagScale(dof.M_SCALE_2GS);
00137 
00138 // Set output data rates
00139 // Accelerometer output data rate (ODR) can be: A_ODR_3125 (3.225 Hz), A_ODR_625 (6.25 Hz), A_ODR_125 (12.5 Hz), A_ODR_25, A_ODR_50,
00140 //                                              A_ODR_100,  A_ODR_200, A_ODR_400, A_ODR_800, A_ODR_1600 (1600 Hz)
00141     dof.setAccelODR(dof.A_ODR_200); // Set accelerometer update rate at 100 Hz
00142 // Accelerometer anti-aliasing filter rate can be 50, 194, 362, or 763 Hz
00143 // Anti-aliasing acts like a low-pass filter allowing oversampling of accelerometer and rejection of high-frequency spurious noise.
00144 // Strategy here is to effectively oversample accelerometer at 100 Hz and use a 50 Hz anti-aliasing (low-pass) filter frequency
00145 // to get a smooth ~150 Hz filter update rate
00146     dof.setAccelABW(dof.A_ABW_50); // Choose lowest filter setting for low noise
00147 
00148 // Gyro output data rates can be: 95 Hz (bandwidth 12.5 or 25 Hz), 190 Hz (bandwidth 12.5, 25, 50, or 70 Hz)
00149 //                                 380 Hz (bandwidth 20, 25, 50, 100 Hz), or 760 Hz (bandwidth 30, 35, 50, 100 Hz)
00150     dof.setGyroODR(dof.G_ODR_190_BW_125);  // Set gyro update rate to 190 Hz with the smallest bandwidth for low noise
00151 
00152 // Magnetometer output data rate can be: 3.125 (ODR_3125), 6.25 (ODR_625), 12.5 (ODR_125), 25, 50, or 100 Hz
00153     dof.setMagODR(dof.M_ODR_125); // Set magnetometer to update every 80 ms
00154 
00155 // Use the FIFO mode to average accelerometer and gyro readings to calculate the biases, which can then be removed from
00156 // all subsequent measurements.
00157     dof.calLSM9DS0(gbias, abias);
00158 
00159 // Start timers to get integration time and print time
00160     t2.start();
00161     t1.start();
00162     dataGyro();
00163     dataAccel();
00164     dataMag();
00165 }
00166 
00167 void loop()
00168 {
00169     //Couldn't manage to get these in interrupt, the interrupt won't fire. It isn't so nececesary indeed.
00170     if(INT1XM.read())
00171         dataAccel();
00172     if(INT2XM.read()) 
00173     {
00174         dataMag();
00175        // dof.readTemp(); Can't get temp reading from a Sparkfun breakout board, the problem is not just mine.
00176         //temperature = 21.0 + (float) dof.temperature/8.0f; // slope is 8 LSB per degree C, just guessing at the intercept
00177     }
00178     if(DRDYG.read())
00179         dataGyro();
00180 
00181     deltat = t1.read(); // set integration time by time elapsed since last filter update
00182     t1.reset();
00183 
00184     // Sensors x- and y-axes are aligned but magnetometer z-axis (+ down) is opposite to z-axis (+ up) of accelerometer and gyro!
00185     // This is ok by aircraft orientation standards!
00186     // Pass gyro rate as rad/s
00187     MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, mx, my, mz);
00188 //MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, mx, my, mz);
00189 
00190 
00191     // Serial print at 0.5 s rate independent of data rates
00192     if (t2.read() > 1.0f) {
00193         t2.reset();
00194 
00195         myled = !myled;
00196 
00197         pc.printf("%f\t%f\t%f\n\r", ax, ay, az);
00198         pc.printf("%f\t%f\t%f\n\r", gx, gy, gz);
00199         pc.printf("%f\t%f\t%f\n\r", mx, my, mz);
00200         /*
00201          // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation.
00202          // In this coordinate system, the positive z-axis is down toward Earth.
00203          // Yaw is the angle between Sensor x-axis and Earth magnetic North (or true North if corrected for local declination),
00204          // looking down on the sensor positive yaw is counterclockwise.
00205          // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative.
00206          // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll.
00207          // These arise from the definition of the homogeneous rotation matrix constructed from quaternions.
00208          // Tait-Bryan angles as well as Euler angles are non-commutative; that is, to get the correct orientation the rotations must be
00209          // applied in the correct order which for this configuration is yaw, pitch, and then roll.
00210          // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links.
00211          */
00212         yaw   = atan2(2.0f * (q[1] * q[2] + q[0] * q[3]), q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]);
00213         pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2]));
00214         roll  = atan2(2.0f * (q[0] * q[1] + q[2] * q[3]), q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]);
00215         pitch *= 180.0f / PI;
00216         yaw   *= 180.0f / PI;
00217         roll  *= 180.0f / PI;
00218         //yaw   -= 13.8; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04
00219 
00220 /*
00221         pc.printf("Temperature = ");
00222         pc.printf("%d\n\r", dof.temperature);
00223 */
00224         //Angles print
00225         pc.printf("Yaw, Pitch, Roll: ");
00226         pc.printf("%f", yaw);
00227         pc.printf(", ");
00228         pc.printf("%f", pitch);
00229         pc.printf(", ");
00230         pc.printf("%f\n\r", roll);
00231 
00232         //Update rate print
00233         pc.printf("Filter rate = ");
00234         pc.printf("%f\n\r", 1.0f/deltat);
00235 
00236         /*
00237         // The filter update rate can be increased by reducing the rate of data reading. The optimal implementation is
00238         // one which balances the competing rates so they are about the same; that is, the filter updates the sensor orientation
00239         // at about the same rate the data is changing. Of course, other implementations are possible. One might consider
00240         // updating the filter at twice the average new data rate to allow for finite filter convergence times.
00241         // The filter update rate is determined mostly by the mathematical steps in the respective algorithms,
00242         // the processor speed (8 MHz for the 3.3V Pro Mini), and the sensor ODRs, especially the magnetometer ODR:
00243         // smaller ODRs for the magnetometer produce the above rates, maximum magnetometer ODR of 100 Hz produces
00244         // filter update rates of ~110 and ~135 Hz for the Madgwick and Mahony schemes, respectively.
00245         // This is presumably because the magnetometer read takes longer than the gyro or accelerometer reads.
00246         // With low ODR settings of 100 Hz, 95 Hz, and 6.25 Hz for the accelerometer, gyro, and magnetometer, respectively,
00247         // the filter is updating at a ~150 Hz rate using the Madgwick scheme and ~200 Hz using the Mahony scheme.
00248         // These filter update rates should be fast enough to maintain accurate platform orientation for
00249         // stabilization control of a fast-moving robot or quadcopter. Compare to the update rate of 200 Hz
00250         // produced by the on-board Digital Motion Processor of Invensense's MPU6050 6 DoF and MPU9150 9DoF sensors.
00251         // The 3.3 V 8 MHz Pro Mini is doing pretty well!
00252         */
00253     }
00254 }
00255 
00256 
00257 
00258 
00259 // Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays"
00260 // (see http://www.x-io.co.uk/category/open-source/ for examples and more details)
00261 // which fuses acceleration, rotation rate, and magnetic moments to produce a quaternion-based estimate of absolute
00262 // device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc.
00263 // The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms
00264 // but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz!
00265 void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz)
00266 {
00267     float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3];   // short name local variable for readability
00268     float norm;
00269     float hx, hy, _2bx, _2bz;
00270     float s1, s2, s3, s4;
00271     float qDot1, qDot2, qDot3, qDot4;
00272 
00273     // Auxiliary variables to avoid repeated arithmetic
00274     float _2q1mx;
00275     float _2q1my;
00276     float _2q1mz;
00277     float _2q2mx;
00278     float _4bx;
00279     float _4bz;
00280     float _2q1 = 2.0f * q1;
00281     float _2q2 = 2.0f * q2;
00282     float _2q3 = 2.0f * q3;
00283     float _2q4 = 2.0f * q4;
00284     float _2q1q3 = 2.0f * q1 * q3;
00285     float _2q3q4 = 2.0f * q3 * q4;
00286     float q1q1 = q1 * q1;
00287     float q1q2 = q1 * q2;
00288     float q1q3 = q1 * q3;
00289     float q1q4 = q1 * q4;
00290     float q2q2 = q2 * q2;
00291     float q2q3 = q2 * q3;
00292     float q2q4 = q2 * q4;
00293     float q3q3 = q3 * q3;
00294     float q3q4 = q3 * q4;
00295     float q4q4 = q4 * q4;
00296 
00297     // Normalise accelerometer measurement
00298     norm = sqrt(ax * ax + ay * ay + az * az);
00299     if (norm == 0.0f) return; // handle NaN
00300     norm = 1.0f/norm;
00301     ax *= norm;
00302     ay *= norm;
00303     az *= norm;
00304 
00305     // Normalise magnetometer measurement
00306     norm = sqrt(mx * mx + my * my + mz * mz);
00307     if (norm == 0.0f) return; // handle NaN
00308     norm = 1.0f/norm;
00309     mx *= norm;
00310     my *= norm;
00311     mz *= norm;
00312 
00313     // Reference direction of Earth's magnetic field
00314     _2q1mx = 2.0f * q1 * mx;
00315     _2q1my = 2.0f * q1 * my;
00316     _2q1mz = 2.0f * q1 * mz;
00317     _2q2mx = 2.0f * q2 * mx;
00318     hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4;
00319     hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4;
00320     _2bx = sqrt(hx * hx + hy * hy);
00321     _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4;
00322     _4bx = 2.0f * _2bx;
00323     _4bz = 2.0f * _2bz;
00324 
00325     // Gradient decent algorithm corrective step
00326     s1 = -_2q3 * (2.0f * q2q4 - _2q1q3 - ax) + _2q2 * (2.0f * q1q2 + _2q3q4 - ay) - _2bz * q3 * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (-_2bx * q4 + _2bz * q2) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + _2bx * q3 * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz);
00327     s2 = _2q4 * (2.0f * q2q4 - _2q1q3 - ax) + _2q1 * (2.0f * q1q2 + _2q3q4 - ay) - 4.0f * q2 * (1.0f - 2.0f * q2q2 - 2.0f * q3q3 - az) + _2bz * q4 * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (_2bx * q3 + _2bz * q1) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + (_2bx * q4 - _4bz * q2) * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz);
00328     s3 = -_2q1 * (2.0f * q2q4 - _2q1q3 - ax) + _2q4 * (2.0f * q1q2 + _2q3q4 - ay) - 4.0f * q3 * (1.0f - 2.0f * q2q2 - 2.0f * q3q3 - az) + (-_4bx * q3 - _2bz * q1) * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (_2bx * q2 + _2bz * q4) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + (_2bx * q1 - _4bz * q3) * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz);
00329     s4 = _2q2 * (2.0f * q2q4 - _2q1q3 - ax) + _2q3 * (2.0f * q1q2 + _2q3q4 - ay) + (-_4bx * q4 + _2bz * q2) * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (-_2bx * q1 + _2bz * q3) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + _2bx * q2 * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz);
00330     norm = sqrt(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4);    // normalise step magnitude
00331     norm = 1.0f/norm;
00332     s1 *= norm;
00333     s2 *= norm;
00334     s3 *= norm;
00335     s4 *= norm;
00336 
00337     // Compute rate of change of quaternion
00338     qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - beta * s1;
00339     qDot2 = 0.5f * (q1 * gx + q3 * gz - q4 * gy) - beta * s2;
00340     qDot3 = 0.5f * (q1 * gy - q2 * gz + q4 * gx) - beta * s3;
00341     qDot4 = 0.5f * (q1 * gz + q2 * gy - q3 * gx) - beta * s4;
00342 
00343     // Integrate to yield quaternion
00344     q1 += qDot1 * deltat;
00345     q2 += qDot2 * deltat;
00346     q3 += qDot3 * deltat;
00347     q4 += qDot4 * deltat;
00348     norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4);    // normalise quaternion
00349     norm = 1.0f/norm;
00350     q[0] = q1 * norm;
00351     q[1] = q2 * norm;
00352     q[2] = q3 * norm;
00353     q[3] = q4 * norm;
00354 
00355 }
00356 
00357 
00358 
00359 // Similar to Madgwick scheme but uses proportional and integral filtering on the error between estimated reference vectors and
00360 // measured ones.
00361 void MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz)
00362 {
00363     float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3];   // short name local variable for readability
00364     float norm;
00365     float hx, hy, bx, bz;
00366     float vx, vy, vz, wx, wy, wz;
00367     float ex, ey, ez;
00368     float pa, pb, pc;
00369 
00370     // Auxiliary variables to avoid repeated arithmetic
00371     float q1q1 = q1 * q1;
00372     float q1q2 = q1 * q2;
00373     float q1q3 = q1 * q3;
00374     float q1q4 = q1 * q4;
00375     float q2q2 = q2 * q2;
00376     float q2q3 = q2 * q3;
00377     float q2q4 = q2 * q4;
00378     float q3q3 = q3 * q3;
00379     float q3q4 = q3 * q4;
00380     float q4q4 = q4 * q4;
00381 
00382     // Normalise accelerometer measurement
00383     norm = sqrt(ax * ax + ay * ay + az * az);
00384     if (norm == 0.0f) return; // handle NaN
00385     norm = 1.0f / norm;        // use reciprocal for division
00386     ax *= norm;
00387     ay *= norm;
00388     az *= norm;
00389 
00390     // Normalise magnetometer measurement
00391     norm = sqrt(mx * mx + my * my + mz * mz);
00392     if (norm == 0.0f) return; // handle NaN
00393     norm = 1.0f / norm;        // use reciprocal for division
00394     mx *= norm;
00395     my *= norm;
00396     mz *= norm;
00397 
00398     // Reference direction of Earth's magnetic field
00399     hx = 2.0f * mx * (0.5f - q3q3 - q4q4) + 2.0f * my * (q2q3 - q1q4) + 2.0f * mz * (q2q4 + q1q3);
00400     hy = 2.0f * mx * (q2q3 + q1q4) + 2.0f * my * (0.5f - q2q2 - q4q4) + 2.0f * mz * (q3q4 - q1q2);
00401     bx = sqrt((hx * hx) + (hy * hy));
00402     bz = 2.0f * mx * (q2q4 - q1q3) + 2.0f * my * (q3q4 + q1q2) + 2.0f * mz * (0.5f - q2q2 - q3q3);
00403 
00404     // Estimated direction of gravity and magnetic field
00405     vx = 2.0f * (q2q4 - q1q3);
00406     vy = 2.0f * (q1q2 + q3q4);
00407     vz = q1q1 - q2q2 - q3q3 + q4q4;
00408     wx = 2.0f * bx * (0.5f - q3q3 - q4q4) + 2.0f * bz * (q2q4 - q1q3);
00409     wy = 2.0f * bx * (q2q3 - q1q4) + 2.0f * bz * (q1q2 + q3q4);
00410     wz = 2.0f * bx * (q1q3 + q2q4) + 2.0f * bz * (0.5f - q2q2 - q3q3);
00411 
00412     // Error is cross product between estimated direction and measured direction of gravity
00413     ex = (ay * vz - az * vy) + (my * wz - mz * wy);
00414     ey = (az * vx - ax * vz) + (mz * wx - mx * wz);
00415     ez = (ax * vy - ay * vx) + (mx * wy - my * wx);
00416     if (Ki > 0.0f) {
00417         eInt[0] += ex;      // accumulate integral error
00418         eInt[1] += ey;
00419         eInt[2] += ez;
00420     } else {
00421         eInt[0] = 0.0f;     // prevent integral wind up
00422         eInt[1] = 0.0f;
00423         eInt[2] = 0.0f;
00424     }
00425 
00426     // Apply feedback terms
00427     gx = gx + Kp * ex + Ki * eInt[0];
00428     gy = gy + Kp * ey + Ki * eInt[1];
00429     gz = gz + Kp * ez + Ki * eInt[2];
00430 
00431     // Integrate rate of change of quaternion
00432     pa = q2;
00433     pb = q3;
00434     pc = q4;
00435     q1 = q1 + (-q2 * gx - q3 * gy - q4 * gz) * (0.5f * deltat);
00436     q2 = pa + (q1 * gx + pb * gz - pc * gy) * (0.5f * deltat);
00437     q3 = pb + (q1 * gy - pa * gz + pc * gx) * (0.5f * deltat);
00438     q4 = pc + (q1 * gz + pa * gy - pb * gx) * (0.5f * deltat);
00439 
00440     // Normalise quaternion
00441     norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4);
00442     norm = 1.0f / norm;
00443     q[0] = q1 * norm;
00444     q[1] = q2 * norm;
00445     q[2] = q3 * norm;
00446     q[3] = q4 * norm;
00447 
00448 }