Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Revision 3:e7be5e23013d, committed 2022-07-25
- Comitter:
 - AkiraHeya
 - Date:
 - Mon Jul 25 05:54:41 2022 +0000
 - Parent:
 - 2:4e59a37182df
 - Commit message:
 - IMU-MPU9250-TestCode
 
Changed in this revision
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/EKF.h	Mon Jul 25 05:54:41 2022 +0000
@@ -0,0 +1,115 @@
+//------------------------------------------------------------------------------
+// Extended Kalman Filter for a sensor fusion (Gyroscope and accelataion sensor)
+//------------------------------------------------------------------------------
+#ifndef EKF_H
+#define EKF_H
+
+#include "mbed.h"
+#include "math.h"
+#include "Eigen/Core.h"
+#include "Eigen/Geometry.h"
+using namespace Eigen;
+
+//----Variables
+float wx, wy, wz;
+float s_pre_a, s_pre_b, c_pre_a, c_pre_b;
+float preEst_a, preEst_b;
+float s2_pre_a, c2_pre_a;
+float af1_a, af1_b, af2_a, af2_b;
+float pre_a = 0.0;
+float pre_b = 0.0;
+float estAlpha, estBeta;
+float b = 1.0f;
+//--For check
+float xhat0, xhat1;
+float af00, af01, af10, af11;
+float P00, P01, P10, P11;
+float KG00, KG01, KG10, KG11;
+float eye00, eye01, eye10, eye11;
+
+//----Vector
+Vector2f y;
+Vector2f h;
+Vector2f xhat;
+Vector2f xhat_new;
+
+//----Matrix
+Matrix2f eye = Matrix2f::Identity();
+Matrix2f af;
+Matrix2f ah = eye;
+Matrix2f P = 1*eye;
+Matrix2f pre_P = 1*eye;
+Matrix2f P_new;
+Matrix2f KG_den;    // denominator of kalman gain
+Matrix2f KalmanGain;
+Matrix2f Q = 0.001*eye; // Covariance matrix
+Matrix2f R = 0.001*eye;
+
+class EKF
+{
+  protected:
+    
+  public:
+  void ExtendedKalmanFilterUpdate(float th_ax, float th_ay, float pre_wx, float pre_wy, float pre_wz)
+  {
+    //----Prediction step
+    //--Previous estimated state
+    s_pre_a = sin(pre_a);
+    c_pre_a = cos(pre_a);
+    s_pre_b = sin(pre_b);
+    c_pre_b = cos(pre_b);
+    
+    // PreEst alpha, beta
+    xhat(0) = pre_a + delt_t*(pre_wx*(c_pre_a*c_pre_a*c_pre_b + s_pre_a*s_pre_a*s_pre_b) + pre_wy*(s_pre_a*s_pre_b) - pre_wz*(c_pre_a*c_pre_b));
+    xhat0 = xhat(0);
+    xhat(1) = pre_b + delt_t*(pre_wy*c_pre_a*c_pre_b + pre_wz*s_pre_a*s_pre_b);
+    xhat1 = xhat(1);
+    
+    //--Linearized system
+    s2_pre_a = sin(2.0f*pre_a);
+    c2_pre_a = cos(2.0f*pre_a);
+    // af1_a, af1_b, af2_a, af2_b
+    af(0,0) = 1.0f + delt_t*(pre_wx*(-s2_pre_a*c_pre_b + s2_pre_a*s_pre_b) + pre_wy*c_pre_a*s_pre_b);
+    af(0,1) = delt_t*(-pre_wx*(c_pre_a*c_pre_a*s_pre_b + s_pre_b*s_pre_a*c_pre_b) + pre_wy*s_pre_a*c_pre_b);
+    af(1,0) = delt_t*(-pre_wy*s_pre_a*c_pre_b + pre_wz*c_pre_a*s_pre_b);
+    af(1,1) = 1.0f + delt_t*(-pre_wy*(c_pre_a*s_pre_b) + pre_wz*(s_pre_a*c_pre_b));
+    
+    //--Previous error covariance matrix
+    P = af*pre_P*af.transpose() + b*Q*b;
+    
+    //----Filtering step
+    //--Kalman gain calulation
+    KG_den = ah.transpose()*P*ah + R;
+    KalmanGain = (P*ah)*KG_den.inverse();
+    
+    /*
+    KG00 = KalmanGain(0,0);
+    KG01 = KalmanGain(0,1);
+    KG10 = KalmanGain(1,0);
+    KG11 = KalmanGain(1,1);
+    */
+    
+    //--New Estimated state
+    h(0) = xhat0;
+    h(1) = xhat1;
+    y(0) = th_ax;
+    y(1) = th_ay;
+    xhat_new = xhat + KalmanGain*(y - h);
+    estAlpha = xhat_new(0);
+    estBeta = xhat_new(1);
+    
+    //--New covariance matrix
+    P_new = (eye - KalmanGain*ah.transpose())*P;
+    
+    //--Set the current value as previous value
+    pre_wx = wx;
+    pre_wy = wy;
+    pre_wz = wz;
+    pre_th_ax = th_ax;
+    pre_th_ay = th_ay;
+    pre_P = P_new;
+    pre_a = estAlpha;
+    pre_b = estBeta;    
+  }
+};
+#endif
--- a/MPU9250.h	Tue Aug 05 01:37:23 2014 +0000
+++ b/MPU9250.h	Mon Jul 25 05:54:41 2022 +0000
@@ -1,12 +1,12 @@
+//------------------------------------------------------------------------------
+// Attitude measurement using IMU(MPU-9250)
+//------------------------------------------------------------------------------
 #ifndef MPU9250_H
 #define MPU9250_H
  
 #include "mbed.h"
 #include "math.h"
- 
-// See also MPU-9250 Register Map and Descriptions, Revision 4.0, RM-MPU-9250A-00, Rev. 1.4, 9/9/2013 for registers not listed in 
-// above document; the MPU9250 and MPU9150 are virtually identical but the latter has a different register map
-//
+
 //Magnetometer Registers
 #define AK8963_ADDRESS   0x0C<<1
 #define WHO_AM_I_AK8963  0x00 // should return 0x48
@@ -30,7 +30,8 @@
 #define SELF_TEST_Y_GYRO 0x01                                                                          
 #define SELF_TEST_Z_GYRO 0x02
 
-/*#define X_FINE_GAIN      0x03 // [7:0] fine gain
+/*
+#define X_FINE_GAIN      0x03 // [7:0] fine gain
 #define Y_FINE_GAIN      0x04
 #define Z_FINE_GAIN      0x05
 #define XA_OFFSET_H      0x06 // User-defined trim values for accelerometer
@@ -38,7 +39,8 @@
 #define YA_OFFSET_H      0x08
 #define YA_OFFSET_L_TC   0x09
 #define ZA_OFFSET_H      0x0A
-#define ZA_OFFSET_L_TC   0x0B */
+#define ZA_OFFSET_L_TC   0x0B 
+*/
 
 #define SELF_TEST_X_ACCEL 0x0D
 #define SELF_TEST_Y_ACCEL 0x0E    
@@ -153,7 +155,6 @@
 #define ZA_OFFSET_H      0x7D
 #define ZA_OFFSET_L      0x7E
 
-// Using the MSENSR-9250 breakout board, ADO is set to 0 
 // Seven-bit device address is 110100 for ADO = 0 and 110101 for ADO = 1
 //mbed uses the eight-bit device address, so shift seven-bit addresses left by one!
 #define ADO 0
@@ -190,25 +191,27 @@
 float aRes, gRes, mRes;      // scale resolutions per LSB for the sensors
 
 //Set up I2C, (SDA,SCL)
-I2C i2c(I2C_SDA, I2C_SCL);
+I2C i2c(p9, p10);
 
-DigitalOut myled(LED1);
-    
 // Pin definitions
-int intPin = 12;  // These can be changed, 2 and 3 are the Arduinos ext int pins
-
 int16_t accelCount[3];  // Stores the 16-bit signed accelerometer sensor output
 int16_t gyroCount[3];   // Stores the 16-bit signed gyro sensor output
 int16_t magCount[3];    // Stores the 16-bit signed magnetometer sensor output
 float magCalibration[3] = {0, 0, 0}, magbias[3] = {0, 0, 0};  // Factory mag calibration and mag bias
 float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}; // Bias corrections for gyro and accelerometer
-float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values 
+float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values
+float th_ax, th_ay, th_az;
+float th_ax_LPF, th_ay_LPF, th_az_LPF;
+float pre_th_ax, pre_th_ay, pre_th_az;
+float th_gx, th_gy, th_gz;
+float pre_gx, pre_gy, pre_gz;
+float th_x, th_y, th_z, th_x_d, th_y_d, th_z_d;
 int16_t tempCount;   // Stores the real internal chip temperature in degrees Celsius
 float temperature;
 float SelfTest[6];
 
-int delt_t = 0; // used to control display output rate
-int count = 0;  // used to control display output rate
+float delt_t = 0.0f; // used to display output rate
+float sum_dt = 0.0f; // 
 
 // parameters for 6 DoF sensor fusion calculations
 float PI = 3.14159265358979323846f;
@@ -221,7 +224,7 @@
 
 float pitch, yaw, roll;
 float deltat = 0.0f;                             // integration interval for both filter schemes
-int lastUpdate = 0, firstUpdate = 0, Now = 0;    // used to calculate integration interval                               // used to calculate integration interval
+float lastUpdate = 0.0f, firstUpdate = 0.0f, Now = 0.0f;  // used to calculate integration interval                               // used to calculate integration interval
 float q[4] = {1.0f, 0.0f, 0.0f, 0.0f};           // vector to hold quaternion
 float eInt[3] = {0.0f, 0.0f, 0.0f};              // vector to hold integral error for Mahony method
 
@@ -263,7 +266,6 @@
      dest[ii] = data[ii];
     }
 } 
- 
 
 void getMres() {
   switch (Mscale)
@@ -279,7 +281,6 @@
   }
 }
 
-
 void getGres() {
   switch (Gscale)
   {
@@ -301,7 +302,6 @@
   }
 }
 
-
 void getAres() {
   switch (Ascale)
   {
@@ -348,11 +348,12 @@
   if(readByte(AK8963_ADDRESS, AK8963_ST1) & 0x01) { // wait for magnetometer data ready bit to be set
   readBytes(AK8963_ADDRESS, AK8963_XOUT_L, 7, &rawData[0]);  // Read the six raw data and ST2 registers sequentially into data array
   uint8_t c = rawData[6]; // End data read by reading ST2 register
-    if(!(c & 0x08)) { // Check if magnetic sensor overflow set, if not then report data
+    if(!(c & 0x08)) 
+    { // Check if magnetic sensor overflow set, if not then report data
     destination[0] = (int16_t)(((int16_t)rawData[1] << 8) | rawData[0]);  // Turn the MSB and LSB into a signed 16-bit value
     destination[1] = (int16_t)(((int16_t)rawData[3] << 8) | rawData[2]) ;  // Data stored as little Endian
     destination[2] = (int16_t)(((int16_t)rawData[5] << 8) | rawData[4]) ; 
-   }
+    }
   }
 }
 
@@ -364,11 +365,12 @@
 }
 
 
-void resetMPU9250() {
+void resetMPU9250()
+{
   // reset device
   writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
   wait(0.1);
-  }
+}
   
   void initAK8963(float * destination)
 {
@@ -428,7 +430,7 @@
  // It is possible to get a 4 kHz sample rate from the accelerometer by choosing 1 for
  // accel_fchoice_b bit [3]; in this case the bandwidth is 1.13 kHz
   c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG2);
-  writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c & ~0x0F); // Clear accel_fchoice_b (bit 3) and A_DLPFG (bits [2:0])  
+  writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c & ~0x0F); // Clear accel_fchoice_b (bit 3) and A_DLPFG (bits [2:0])
   writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c | 0x03); // Set accelerometer rate to 1 kHz and bandwidth to 41 Hz
 
  // The accelerometer, gyro, and thermometer are set to 1 kHz sample rates, 
@@ -488,7 +490,8 @@
   fifo_count = ((uint16_t)data[0] << 8) | data[1];
   packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging
 
-  for (ii = 0; ii < packet_count; ii++) {
+  for (ii = 0; ii < packet_count; ii++)
+  {
     int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0};
     readBytes(MPU9250_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging
     accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1]  ) ;  // Form signed 16-bit integer for each sample in FIFO
@@ -503,9 +506,9 @@
     accel_bias[2] += (int32_t) accel_temp[2];
     gyro_bias[0]  += (int32_t) gyro_temp[0];
     gyro_bias[1]  += (int32_t) gyro_temp[1];
-    gyro_bias[2]  += (int32_t) gyro_temp[2];
-            
-}
+    gyro_bias[2]  += (int32_t) gyro_temp[2];        
+    }
+    
     accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases
     accel_bias[1] /= (int32_t) packet_count;
     accel_bias[2] /= (int32_t) packet_count;
@@ -513,16 +516,16 @@
     gyro_bias[1]  /= (int32_t) packet_count;
     gyro_bias[2]  /= (int32_t) packet_count;
     
-  if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) accelsensitivity;}  // Remove gravity from the z-axis accelerometer bias calculation
-  else {accel_bias[2] += (int32_t) accelsensitivity;}
+    if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) accelsensitivity;}  // Remove gravity from the z-axis accelerometer bias calculation
+    else {accel_bias[2] += (int32_t) accelsensitivity;}
  
-// Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup
-  data[0] = (-gyro_bias[0]/4  >> 8) & 0xFF; // Divide by 4 to get 32.9 LSB per deg/s to conform to expected bias input format
-  data[1] = (-gyro_bias[0]/4)       & 0xFF; // Biases are additive, so change sign on calculated average gyro biases
-  data[2] = (-gyro_bias[1]/4  >> 8) & 0xFF;
-  data[3] = (-gyro_bias[1]/4)       & 0xFF;
-  data[4] = (-gyro_bias[2]/4  >> 8) & 0xFF;
-  data[5] = (-gyro_bias[2]/4)       & 0xFF;
+    // Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup
+    data[0] = (-gyro_bias[0]/4  >> 8) & 0xFF; // Divide by 4 to get 32.9 LSB per deg/s to conform to expected bias input format
+    data[1] = (-gyro_bias[0]/4)       & 0xFF; // Biases are additive, so change sign on calculated average gyro biases
+    data[2] = (-gyro_bias[1]/4  >> 8) & 0xFF;
+    data[3] = (-gyro_bias[1]/4)       & 0xFF;
+    data[4] = (-gyro_bias[2]/4  >> 8) & 0xFF;
+    data[5] = (-gyro_bias[2]/4)       & 0xFF;
 
 /// Push gyro biases to hardware registers
 /*  writeByte(MPU9250_ADDRESS, XG_OFFSET_H, data[0]);
@@ -532,9 +535,9 @@
   writeByte(MPU9250_ADDRESS, ZG_OFFSET_H, data[4]);
   writeByte(MPU9250_ADDRESS, ZG_OFFSET_L, data[5]);
 */
-  dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; // construct gyro bias in deg/s for later manual subtraction
-  dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity;
-  dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity;
+    dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; // construct gyro bias in deg/s for later manual subtraction
+    dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity;
+    dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity;
 
 // Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain
 // factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold
@@ -542,35 +545,35 @@
 // compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that
 // the accelerometer biases calculated above must be divided by 8.
 
-  int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases
-  readBytes(MPU9250_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values
-  accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1];
-  readBytes(MPU9250_ADDRESS, YA_OFFSET_H, 2, &data[0]);
-  accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1];
-  readBytes(MPU9250_ADDRESS, ZA_OFFSET_H, 2, &data[0]);
-  accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1];
+    int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases
+    readBytes(MPU9250_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values
+    accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1];
+    readBytes(MPU9250_ADDRESS, YA_OFFSET_H, 2, &data[0]);
+    accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1];
+    readBytes(MPU9250_ADDRESS, ZA_OFFSET_H, 2, &data[0]);
+    accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1];
   
-  uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers
-  uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis
+    uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers
+    uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis
   
-  for(ii = 0; ii < 3; ii++) {
-    if(accel_bias_reg[ii] & mask) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit
-  }
+    for(ii = 0; ii < 3; ii++) {
+        if(accel_bias_reg[ii] & mask) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit
+    }
 
-  // Construct total accelerometer bias, including calculated average accelerometer bias from above
-  accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale)
-  accel_bias_reg[1] -= (accel_bias[1]/8);
-  accel_bias_reg[2] -= (accel_bias[2]/8);
+    // Construct total accelerometer bias, including calculated average accelerometer bias from above
+    accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale)
+    accel_bias_reg[1] -= (accel_bias[1]/8);
+    accel_bias_reg[2] -= (accel_bias[2]/8);
  
-  data[0] = (accel_bias_reg[0] >> 8) & 0xFF;
-  data[1] = (accel_bias_reg[0])      & 0xFF;
-  data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers
-  data[2] = (accel_bias_reg[1] >> 8) & 0xFF;
-  data[3] = (accel_bias_reg[1])      & 0xFF;
-  data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers
-  data[4] = (accel_bias_reg[2] >> 8) & 0xFF;
-  data[5] = (accel_bias_reg[2])      & 0xFF;
-  data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers
+    data[0] = (accel_bias_reg[0] >> 8) & 0xFF;
+    data[1] = (accel_bias_reg[0])      & 0xFF;
+    data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers
+    data[2] = (accel_bias_reg[1] >> 8) & 0xFF;
+    data[3] = (accel_bias_reg[1])      & 0xFF;
+    data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers
+    data[4] = (accel_bias_reg[2] >> 8) & 0xFF;
+    data[5] = (accel_bias_reg[2])      & 0xFF;
+    data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers
 
 // Apparently this is not working for the acceleration biases in the MPU-9250
 // Are we handling the temperature correction bit properly?
@@ -617,7 +620,9 @@
   gAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
   }
   
-  for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average current readings
+  for (int ii =0; ii < 3; ii++)
+  {
+  // Get average of 200 values and store as average current readings
   aAvg[ii] /= 200;
   gAvg[ii] /= 200;
   }
@@ -625,22 +630,25 @@
 // Configure the accelerometer for self-test
    writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0xE0); // Enable self test on all three axes and set accelerometer range to +/- 2 g
    writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s
-   delay(25); // Delay a while to let the device stabilize
+   //delay(25); // Delay a while to let the device stabilize
 
-  for( int ii = 0; ii < 200; ii++) { // get average self-test values of gyro and acclerometer
-  
+  for( int ii = 0; ii < 200; ii++)
+  {
+  // get average self-test values of gyro and acclerometer
   readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array
   aSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
   aSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
   aSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
   
-    readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
+  readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
   gSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
   gSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
   gSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
   }
   
-  for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average self-test readings
+  for (int ii =0; ii < 3; ii++)
+  {
+  // Get average of 200 values and store as average self-test readings
   aSTAvg[ii] /= 200;
   gSTAvg[ii] /= 200;
   }
@@ -648,7 +656,7 @@
  // Configure the gyro and accelerometer for normal operation
    writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00);
    writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00);
-   delay(25); // Delay a while to let the device stabilize
+   //delay(25); // Delay a while to let the device stabilize
    
    // Retrieve accelerometer and gyro factory Self-Test Code from USR_Reg
    selfTest[0] = readByte(MPU9250_ADDRESS, SELF_TEST_X_ACCEL); // X-axis accel self-test results
@@ -668,7 +676,8 @@
  
  // Report results as a ratio of (STR - FT)/FT; the change from Factory Trim of the Self-Test Response
  // To get percent, must multiply by 100
-   for (int i = 0; i < 3; i++) {
+   for (int i = 0; i < 3; i++)
+   {
      destination[i] = 100.0*((float)(aSTAvg[i] - aAvg[i]))/factoryTrim[i]; // Report percent differences
      destination[i+3] = 100.0*((float)(gSTAvg[i] - gAvg[i]))/factoryTrim[i+3]; // Report percent differences
    }
--- a/N5110.lib Tue Aug 05 01:37:23 2014 +0000 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,1 +0,0 @@ -http://mbed.org/users/onehorse/code/Adfs/#28c629d0b0d0
--- a/ST_401_84MHZ.lib Tue Aug 05 01:37:23 2014 +0000 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,1 +0,0 @@ -http://mbed.org/users/dreschpe/code/ST_401_84MHZ/#b9343c8b85ec
--- a/main.cpp	Tue Aug 05 01:37:23 2014 +0000
+++ b/main.cpp	Mon Jul 25 05:54:41 2022 +0000
@@ -1,254 +1,129 @@
-/* MPU9250 Basic Example Code
- by: Kris Winer
- date: April 1, 2014
- license: Beerware - Use this code however you'd like. If you 
- find it useful you can buy me a beer some time.
- 
- Demonstrate basic MPU-9250 functionality including parameterizing the register addresses, initializing the sensor, 
- getting properly scaled accelerometer, gyroscope, and magnetometer data out. Added display functions to 
- allow display to on breadboard monitor. Addition of 9 DoF sensor fusion using open source Madgwick and 
- Mahony filter algorithms. Sketch runs on the 3.3 V 8 MHz Pro Mini and the Teensy 3.1.
- 
- SDA and SCL should have external pull-up resistors (to 3.3V).
- 10k resistors are on the EMSENSR-9250 breakout board.
- 
- Hardware setup:
- MPU9250 Breakout --------- Arduino
- VDD ---------------------- 3.3V
- VDDI --------------------- 3.3V
- SDA ----------------------- A4
- SCL ----------------------- A5
- GND ---------------------- GND
- 
- Note: The MPU9250 is an I2C sensor and uses the Arduino Wire library. 
- Because the sensor is not 5V tolerant, we are using a 3.3 V 8 MHz Pro Mini or a 3.3 V Teensy 3.1.
- We have disabled the internal pull-ups used by the Wire library in the Wire.h/twi.c utility file.
- We are also using the 400 kHz fast I2C mode by setting the TWI_FREQ  to 400000L /twi.h utility file.
- */
- 
-//#include "ST_F401_84MHZ.h" 
-//F401_init84 myinit(0);
+//------------------------------------------------------------------------------
+// Attitude measurement using IMU(MPU-9250)
+//------------------------------------------------------------------------------
+//----include
 #include "mbed.h"
 #include "MPU9250.h"
-#include "N5110.h"
-
-// Using NOKIA 5110 monochrome 84 x 48 pixel display
-// pin 9 - Serial clock out (SCLK)
-// pin 8 - Serial data out (DIN)
-// pin 7 - Data/Command select (D/C)
-// pin 5 - LCD chip select (CS)
-// pin 6 - LCD reset (RST)
-//Adafruit_PCD8544 display = Adafruit_PCD8544(9, 8, 7, 5, 6);
-
-float sum = 0;
-uint32_t sumCount = 0;
+//#include "EKF.h"
+//----variable
 char buffer[14];
-
-   MPU9250 mpu9250;
-   
-   Timer t;
-
-   Serial pc(USBTX, USBRX); // tx, rx
-
-   //        VCC,   SCE,  RST,  D/C,  MOSI,S CLK, LED
-   N5110 lcd(PA_8, PB_10, PA_9, PA_6, PA_7, PA_5, PC_7);
-   
-
-        
+//----Instance
+MPU9250 mpu9250;
+Timer t;
+Serial pc(USBTX, USBRX);
+//****MAIN****
 int main()
 {
-  pc.baud(9600);  
-
-  //Set up I2C
-  i2c.frequency(400000);  // use fast (400 kHz) I2C  
-  
-  pc.printf("CPU SystemCoreClock is %d Hz\r\n", SystemCoreClock);   
-  
-  t.start();        
-  
-  lcd.init();
-//  lcd.setBrightness(0.05);
-  
-    
+  //----Serial baud rate
+  pc.baud(921600);
+  //----I2C clock rate
+  i2c.frequency(400000);
+  //----System clock
+  //pc.printf("CPU SystemCoreClock is %d Hz\r\n", SystemCoreClock);
+  //----Timer start
+  t.start();
   // Read the WHO_AM_I register, this is a good test of communication
-  uint8_t whoami = mpu9250.readByte(MPU9250_ADDRESS, WHO_AM_I_MPU9250);  // Read WHO_AM_I register for MPU-9250
-  pc.printf("I AM 0x%x\n\r", whoami); pc.printf("I SHOULD BE 0x71\n\r");
-  
-  if (whoami == 0x71) // WHO_AM_I should always be 0x68
-  {  
-    pc.printf("MPU9250 WHO_AM_I is 0x%x\n\r", whoami);
-    pc.printf("MPU9250 is online...\n\r");
-    lcd.clear();
-    lcd.printString("MPU9250 is", 0, 0);
-    sprintf(buffer, "0x%x", whoami);
-    lcd.printString(buffer, 0, 1);
-    lcd.printString("shoud be 0x71", 0, 2);  
-    wait(1);
-    
-    mpu9250.resetMPU9250(); // Reset registers to default in preparation for device calibration
-    mpu9250.MPU9250SelfTest(SelfTest); // Start by performing self test and reporting values
-    pc.printf("x-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[0]);  
-    pc.printf("y-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[1]);  
-    pc.printf("z-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[2]);  
-    pc.printf("x-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[3]);  
-    pc.printf("y-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[4]);  
-    pc.printf("z-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[5]);  
-    mpu9250.calibrateMPU9250(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers  
-    pc.printf("x gyro bias = %f\n\r", gyroBias[0]);
-    pc.printf("y gyro bias = %f\n\r", gyroBias[1]);
-    pc.printf("z gyro bias = %f\n\r", gyroBias[2]);
-    pc.printf("x accel bias = %f\n\r", accelBias[0]);
-    pc.printf("y accel bias = %f\n\r", accelBias[1]);
-    pc.printf("z accel bias = %f\n\r", accelBias[2]);
-    wait(2);
-    mpu9250.initMPU9250(); 
-    pc.printf("MPU9250 initialized for active data mode....\n\r"); // Initialize device for active mode read of acclerometer, gyroscope, and temperature
-    mpu9250.initAK8963(magCalibration);
-    pc.printf("AK8963 initialized for active data mode....\n\r"); // Initialize device for active mode read of magnetometer
-    pc.printf("Accelerometer full-scale range = %f  g\n\r", 2.0f*(float)(1<<Ascale));
-    pc.printf("Gyroscope full-scale range = %f  deg/s\n\r", 250.0f*(float)(1<<Gscale));
-    if(Mscale == 0) pc.printf("Magnetometer resolution = 14  bits\n\r");
-    if(Mscale == 1) pc.printf("Magnetometer resolution = 16  bits\n\r");
-    if(Mmode == 2) pc.printf("Magnetometer ODR = 8 Hz\n\r");
-    if(Mmode == 6) pc.printf("Magnetometer ODR = 100 Hz\n\r");
-    wait(1);
-   }
-   else
-   {
-    pc.printf("Could not connect to MPU9250: \n\r");
-    pc.printf("%#x \n",  whoami);
- 
-    lcd.clear();
-    lcd.printString("MPU9250", 0, 0);
-    lcd.printString("no connection", 0, 1);
-    sprintf(buffer, "WHO_AM_I 0x%x", whoami);
-    lcd.printString(buffer, 0, 2); 
- 
-    while(1) ; // Loop forever if communication doesn't happen
+  uint8_t whoami = mpu9250.readByte(MPU9250_ADDRESS, WHO_AM_I_MPU9250);
+  pc.printf("I2C check : 0x%x\n\r", whoami);
+  //----Self check
+    if (whoami == 0x71)
+    {
+        pc.printf("MPU9250 is online\n\r");
+        sprintf(buffer, "0x%x", whoami);
+        wait(3);
+        //----Reset registers to default in preparation for device calibration
+        mpu9250.resetMPU9250();
+        //----Start by performing self test and reporting values
+        mpu9250.MPU9250SelfTest(SelfTest);
+        pc.printf("x-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[0]);
+        pc.printf("y-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[1]);
+        pc.printf("z-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[2]);
+        pc.printf("x-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[3]);
+        pc.printf("y-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[4]);
+        pc.printf("z-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[5]);
+        // Calibrate gyro and accelerometers, load biases in bias registers
+        mpu9250.calibrateMPU9250(gyroBias, accelBias);
+        pc.printf("x gyro bias = %f\n\r", gyroBias[0]);
+        pc.printf("y gyro bias = %f\n\r", gyroBias[1]);
+        pc.printf("z gyro bias = %f\n\r", gyroBias[2]);
+        pc.printf("x accel bias = %f\n\r", accelBias[0]);
+        pc.printf("y accel bias = %f\n\r", accelBias[1]);
+        pc.printf("z accel bias = %f\n\r", accelBias[2]);
+        wait(3);
+        //----Initialize device for active mode read of acclerometer, gyroscope, and temperature
+        mpu9250.initMPU9250();
+        pc.printf("MPU9250 initialized for active data mode....\n\r");
+        pc.printf("Accelerometer full-scale range = %f  g\n\r", 2.0f*(float)(1<<Ascale));
+        pc.printf("Gyroscope full-scale range = %f  deg/s\n\r", 250.0f*(float)(1<<Gscale));
+        wait(3);
     }
-
-    mpu9250.getAres(); // Get accelerometer sensitivity
-    mpu9250.getGres(); // Get gyro sensitivity
-    mpu9250.getMres(); // Get magnetometer sensitivity
+    else
+    {
+        pc.printf("Could not connect to MPU9250: \n\r");
+        pc.printf("%#x \n",  whoami);
+        sprintf(buffer, "WHO_AM_I 0x%x", whoami);
+        //----Loop forever if communication doesn't happen
+        while(1) ;
+    }
+    //----Get accelerometer sensitivity
+    mpu9250.getAres();
+    //----Get gyro sensitivity
+    mpu9250.getGres();
     pc.printf("Accelerometer sensitivity is %f LSB/g \n\r", 1.0f/aRes);
     pc.printf("Gyroscope sensitivity is %f LSB/deg/s \n\r", 1.0f/gRes);
-    pc.printf("Magnetometer sensitivity is %f LSB/G \n\r", 1.0f/mRes);
-    magbias[0] = +470.;  // User environmental x-axis correction in milliGauss, should be automatically calculated
-    magbias[1] = +120.;  // User environmental x-axis correction in milliGauss
-    magbias[2] = +125.;  // User environmental x-axis correction in milliGauss
-
- while(1) {
-  
-  // If intPin goes high, all data registers have new data
-  if(mpu9250.readByte(MPU9250_ADDRESS, INT_STATUS) & 0x01) {  // On interrupt, check if data ready interrupt
-
-    mpu9250.readAccelData(accelCount);  // Read the x/y/z adc values   
-    // Now we'll calculate the accleration value into actual g's
-    ax = (float)accelCount[0]*aRes - accelBias[0];  // get actual g value, this depends on scale being set
-    ay = (float)accelCount[1]*aRes - accelBias[1];   
-    az = (float)accelCount[2]*aRes - accelBias[2];  
-   
-    mpu9250.readGyroData(gyroCount);  // Read the x/y/z adc values
-    // Calculate the gyro value into actual degrees per second
-    gx = (float)gyroCount[0]*gRes - gyroBias[0];  // get actual gyro value, this depends on scale being set
-    gy = (float)gyroCount[1]*gRes - gyroBias[1];  
-    gz = (float)gyroCount[2]*gRes - gyroBias[2];   
-  
-    mpu9250.readMagData(magCount);  // Read the x/y/z adc values   
-    // Calculate the magnetometer values in milliGauss
-    // Include factory calibration per data sheet and user environmental corrections
-    mx = (float)magCount[0]*mRes*magCalibration[0] - magbias[0];  // get actual magnetometer value, this depends on scale being set
-    my = (float)magCount[1]*mRes*magCalibration[1] - magbias[1];  
-    mz = (float)magCount[2]*mRes*magCalibration[2] - magbias[2];   
-  }
-   
-    Now = t.read_us();
-    deltat = (float)((Now - lastUpdate)/1000000.0f) ; // set integration time by time elapsed since last filter update
-    lastUpdate = Now;
     
-    sum += deltat;
-    sumCount++;
-    
-//    if(lastUpdate - firstUpdate > 10000000.0f) {
-//     beta = 0.04;  // decrease filter gain after stabilized
-//     zeta = 0.015; // increasey bias drift gain after stabilized
- //   }
-    
-   // Pass gyro rate as rad/s
-//  mpu9250.MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f,  my,  mx, mz);
-  mpu9250.MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz);
-
-    // Serial print and/or display at 0.5 s rate independent of data rates
-    delt_t = t.read_ms() - count;
-    if (delt_t > 500) { // update LCD once per half-second independent of read rate
-
-    pc.printf("ax = %f", 1000*ax); 
-    pc.printf(" ay = %f", 1000*ay); 
-    pc.printf(" az = %f  mg\n\r", 1000*az); 
+    //****LOOP****
+    while(1)
+    {
+        //----Time interval
+        Now = t.read_us();
+        delt_t = (Now - lastUpdate)/1000000.0f;
+        lastUpdate = Now;
+        // Read the x/y/z adc values
+        mpu9250.readAccelData(accelCount);
+        // Calculate the accleration value into actual g's
+        ax = (float)accelCount[0]*aRes - accelBias[0];  // get actual g value, this depends on scale being set
+        ay = (float)accelCount[1]*aRes - accelBias[1];
+        az = (float)accelCount[2]*aRes - accelBias[2];
+        th_ax = atan2(ay,sqrt(ax*ax+az*az))*(180.0f/PI);
+        th_ay = -1*atan2(ax,az)*(180.0f/PI);
+        // th_az = atan2(az,sqrt(ax*ax+ay*ay))*(180.0f/PI);
+        
+        /*
+        th_ax_LPF = 0.95*pre_th_ax + 0.05*th_ax;
+        th_ay_LPF = 0.95*pre_th_ay + 0.05*th_ay;
+        // th_az_LPF = 0.95*pre_th_az + 0.05*th_az;
+        pre_th_ax = th_ax;
+        pre_th_ay = th_ay;
+        // pre_th_az = th_az;
+        */
 
-    pc.printf("gx = %f", gx); 
-    pc.printf(" gy = %f", gy); 
-    pc.printf(" gz = %f  deg/s\n\r", gz); 
-    
-    pc.printf("gx = %f", mx); 
-    pc.printf(" gy = %f", my); 
-    pc.printf(" gz = %f  mG\n\r", mz); 
-    
-    tempCount = mpu9250.readTempData();  // Read the adc values
-    temperature = ((float) tempCount) / 333.87f + 21.0f; // Temperature in degrees Centigrade
-    pc.printf(" temperature = %f  C\n\r", temperature); 
-    
-    pc.printf("q0 = %f\n\r", q[0]);
-    pc.printf("q1 = %f\n\r", q[1]);
-    pc.printf("q2 = %f\n\r", q[2]);
-    pc.printf("q3 = %f\n\r", q[3]);      
-    
-/*    lcd.clear();
-    lcd.printString("MPU9250", 0, 0);
-    lcd.printString("x   y   z", 0, 1);
-    sprintf(buffer, "%d %d %d mg", (int)(1000.0f*ax), (int)(1000.0f*ay), (int)(1000.0f*az));
-    lcd.printString(buffer, 0, 2);
-    sprintf(buffer, "%d %d %d deg/s", (int)gx, (int)gy, (int)gz);
-    lcd.printString(buffer, 0, 3);
-    sprintf(buffer, "%d %d %d mG", (int)mx, (int)my, (int)mz);
-    lcd.printString(buffer, 0, 4); 
- */  
-  // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation.
-  // In this coordinate system, the positive z-axis is down toward Earth. 
-  // Yaw is the angle between Sensor x-axis and Earth magnetic North (or true North if corrected for local declination, looking down on the sensor positive yaw is counterclockwise.
-  // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative.
-  // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll.
-  // These arise from the definition of the homogeneous rotation matrix constructed from quaternions.
-  // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be
-  // applied in the correct order which for this configuration is yaw, pitch, and then roll.
-  // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links.
-    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]);   
-    pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2]));
-    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]);
-    pitch *= 180.0f / PI;
-    yaw   *= 180.0f / PI; 
-    yaw   -= 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04
-    roll  *= 180.0f / PI;
-
-    pc.printf("Yaw, Pitch, Roll: %f %f %f\n\r", yaw, pitch, roll);
-    pc.printf("average rate = %f\n\r", (float) sumCount/sum);
-//    sprintf(buffer, "YPR: %f %f %f", yaw, pitch, roll);
-//    lcd.printString(buffer, 0, 4);
-//    sprintf(buffer, "rate = %f", (float) sumCount/sum);
-//    lcd.printString(buffer, 0, 5);
-    
-    myled= !myled;
-    count = t.read_ms(); 
-
-    if(count > 1<<21) {
-        t.start(); // start the timer over again if ~30 minutes has passed
-        count = 0;
-        deltat= 0;
-        lastUpdate = t.read_us();
+        // Read the x/y/z adc values
+        mpu9250.readGyroData(gyroCount);
+        // Calculate the gyro value into actual degrees per second
+        gx = (float)gyroCount[0]*gRes - gyroBias[0];  // get actual gyro value, this depends on scale being set
+        gy = (float)gyroCount[1]*gRes - gyroBias[1];
+        gz = (float)gyroCount[2]*gRes - gyroBias[2];
+        
+        th_gx += (pre_gx + gx) * delt_t/2.0f;
+        th_gy += (pre_gy + gy) * delt_t/2.0f;
+        th_gz += (pre_gz + gz) * delt_t/2.0f;
+        pre_gx = gx;
+        pre_gy = gy;
+        pre_gz = gz;
+        
+        //----Complementary filter
+        th_x = 0.95*(th_x + (pre_gx + gx) * delt_t/2.0f) + 0.05*th_ax;
+        th_y = 0.95*(th_y + (pre_gy + gy) * delt_t/2.0f) + 0.05*th_ay;
+        
+        //----Serial print
+        sum_dt += delt_t;
+        if (sum_dt > 0.0050f)
+        {
+            //--Angle from gyroscope and accel sensor [deg.]
+            pc.printf("%8.3f , %8.3f , %8.3f\n", t.read(), th_gx, th_gy);
+            //pc.printf("%8.3f , %8.3f , %8.3f ,%8.3f , %8.3f , %8.3f , %8.3f , %8.3f , %8.3f\n", t.read(), th_ax, th_ay, th_gx, th_gy, th_x, th_y, th_x_d, th_y_d);
+            sum_dt = 0.0f;
+        }
     }
-    sum = 0;
-    sumCount = 0; 
 }
-}
- 
- }
\ No newline at end of file