Filter for 9250

Dependencies:   mbed

main.cpp

Committer:
Edrum_x
Date:
2019-08-06
Revision:
1:c9547742263c
Parent:
0:ccea261dce7a

File content as of revision 1:c9547742263c:

/* 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 "mbed.h"
#include "MPU9250.h"
//#include "ST_F401_84MHZ.h"
#include "f_trapf.h"
#include "f_trapi.h"
#include "f_tri.h"
#include "max_.h"
#include "min_.h"


////////////////GPIO/////////////////////////////////////////////////////////////
PwmOut PWM1(A2);
PwmOut PWM2(PB_1);
PwmOut PWM3(PB_0);

DigitalOut EN1(D2);
DigitalOut EN2(A6);
DigitalOut EN3(D9);

DigitalOut INA1(D10);
DigitalOut INB1(D11);
DigitalOut INA2(D12);
DigitalOut INB2(A0);
DigitalOut INA3(A1);
DigitalOut INB3(A3);
   
///////////////FIN GPIO//////////////////////////////////////////////////////////
int Max_degree=8;
uint8_t area;
int salida;

//funcion de pertenencia para el error
int Ng_e,Np_e,Z_e,Pp_e,Pg_e;

//funcion de pertenencia de delta error
int Ng_de,Np_de,Z_de,Pp_de,Pg_de;

int Ng_u,Ng_u1,Ng_u2,Ng_u3,Ng_u4,Ng_u5,Ng_u6;
int Np_u,Np_u1,Np_u2,Np_u3,Np_u4;
int Z_u,Z_u1,Z_u2,Z_u3,Z_u4,Z_u5;
int Pp_u,Pp_u1,Pp_u2,Pp_u3,Pp_u4;
int Pg_u,Pg_u1,Pg_u2,Pg_u3,Pg_u4,Pg_u5,Pg_u6;




float Modulo=0,error1=0,error2=0,delta_error=0; 
float phi=(2*PI)/3;
float theta;

int a,b,c;



float sum = 0;
uint32_t sumCount = 0;

   MPU9250 mpu9250;
   
   Timer t;

   Serial pc(USBTX, USBRX); // tx, rx

        
int main()
{
  pc.baud(9600);  
  
  //Set up I2C
  i2c.frequency(400000);  // use fast (400 kHz) I2C  
  
    PWM1.period_us(500);
    PWM2.period_us(500);
    PWM3.period_us(500);
  
  
    
  pc.printf("CPU SystemCoreClock is %d Hz\r\n", SystemCoreClock);   
  
  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 == whoami) // WHO_AM_I should always be 0x68
  {  
    pc.printf("MPU9250 is online...\n\r");
    wait(1);
 
    
    mpu9250.resetMPU9250(); // Reset registers to default in preparation for device calibration
    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(2);
   }
   else
   {
    pc.printf("Could not connect to MPU9250: \n\r");
    pc.printf("%#x \n",  whoami);
 
    
 
    while(1) ; // Loop forever if communication doesn't happen
    }

    mpu9250.getAres(); // Get accelerometer sensitivity
    mpu9250.getGres(); // Get gyro sensitivity
    mpu9250.getMres(); // Get magnetometer sensitivity
    //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 > 100) { // 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  ", 1000*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]);      
    
      
  // 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);
 
    myled= !myled;
    //count = t.read_ms(); 
    sum = 0;
    sumCount = 0; 
    //--------------------------------------------------------------------------------------------------------------------------------
    //--------------------------------------------------------------------------------------------------------------------------------
    //-----------------------------------------------MY CODE--------------------------------------------------------------------------
    //--------------------------------------------------------------------------------------------------------------------------------
    //--------------------------------------------------------------------------------------------------------------------------------
    
    Modulo=sqrt(((pitch)*(pitch))+((roll)*(roll)));
        
    theta = atan2(pitch,roll);    
    
    
    //--------------------------------------------------------------------------------------------------------------------------------
    //--------------------------------------------------------------------------------------------------------------------------------
    //-----------------------------------------------FUZZY--------------------------------------------------------------------------
    //--------------------------------------------------------------------------------------------------------------------------------
    //--------------------------------------------------------------------------------------------------------------------------------
    
    error1=Modulo;
    delta_error=(error1-error2)*100;

    error2=error1;


//funcion de pertenencia del error
Ng_e=f_trapi(-Max_degree/2,-Max_degree/4,error1);
Np_e=f_tri(-Max_degree/2,0,error1);
Z_e=f_tri(-Max_degree/4,Max_degree/4,error1);
Pp_e=f_tri(0,Max_degree/2,error1);
Pg_e=f_trapf(Max_degree/4,Max_degree/2,error1);

//funcion de pertenencia de delta error
Ng_de=f_trapi(-Max_degree/4,-Max_degree/8,delta_error);
Np_de=f_tri(-Max_degree/4,0,delta_error);
Z_de=f_tri(-Max_degree/8,Max_degree/8,delta_error);
Pp_de=f_tri(0,Max_degree/4,delta_error);
Pg_de=f_trapf(Max_degree/8,Max_degree/4,delta_error);

//estados de salida Ng

Ng_u1=min_(Ng_e,Ng_de);
Ng_u2=min_(Np_e,Ng_de);
Ng_u3=min_(Z_e,Ng_de);
Ng_u4=min_(Ng_e,Np_de);
Ng_u5=min_(Np_e,Np_de);
Ng_u6=min_(Ng_e,Z_de);

Ng_u=max_(Ng_u1,max_(Ng_u2,max_(Ng_u3,max_(Ng_u4,max_(Ng_u5,Ng_u6)))));

Np_u1=min_(Ng_e,Pp_de);
Np_u2=min_(Np_e,Z_de);
Np_u3=min_(Z_e,Np_de);
Np_u4=min_(Pp_e,Ng_de);

Np_u=max_(Np_u1,max_(Np_u2,max_(Np_u3,Np_u4)));

Z_u1=min_(Ng_e,Pg_de);
Z_u2=min_(Np_e,Pp_de);
Z_u3=min_(Z_e,Z_de);
Z_u4=min_(Pp_e,Np_de);
Z_u5=min_(Pg_e,Ng_de);

Z_u=max_(Z_u1,max_(Z_u2,max_(Z_u3,max_(Z_u4,Z_u5))));

Pp_u1=min_(Pg_e,Np_de);
Pp_u2=min_(Pp_e,Z_de);
Pp_u3=min_(Z_e,Pp_de);
Pp_u4=min_(Np_e,Pg_de);

Pp_u=max_(Pp_u1,max_(Pp_u2,max_(Pp_u3,Pp_u4)));

Pg_u1=min_(Pg_e,Pg_de);
Pg_u2=min_(Pp_e,Pg_de);
Pg_u3=min_(Z_e,Pg_de);
Pg_u4=min_(Pg_e,Pp_de);
Pg_u5=min_(Pp_e,Pp_de);
Pg_u6=min_(Pg_e,Z_de);

Pg_u=max_(Pg_u1,max_(Pg_u2,max_(Pg_u3,max_(Pg_u4,max_(Pg_u5,Pg_u6)))));

area = (25*Ng_u)+(25*Np_u)+(25*Z_u)+(25*Pp_u)+(25*Pg_u)-(12.5*(25/((25/Ng_u)+(25/Np_u))))-(12.5*(25/((25/Np_u)+(25/Z_u))))-(12.5*(25/((25/Z_u)+(25/Pp_u))))-(12.5*(25/((25/Pp_u)+(25/Pg_u))));
salida= ((-50*Ng_u)+(-25*Np_u)+(25*Pp_u)+(50*Pg_u))*25/area;
    
    
    //--------------------------------------------------------------------------------------------------------------------------------
    //--------------------------------------------------------------------------------------------------------------------------------
    //-----------------------------------------------FUZZY END--------------------------------------------------------------------------
    //--------------------------------------------------------------------------------------------------------------------------------
    //--------------------------------------------------------------------------------------------------------------------------------
    
  
    a= (int)(Modulo * sin(theta))*40;
    b= (int)(Modulo * sin(theta-phi))*40;
    c= (int)(Modulo * sin(theta+phi))*40;   
    
    
    
    
    if(a<0){a=-a;    EN1=1;     INA1=0;     INB1=1;}
    else{            EN1=1;     INA1=1;     INB1=0;}
    
    
    if(b<0){b=-b;    EN2=1;     INA2=0;     INB2=1;}
    else{            EN2=1;     INA2=1;     INB2=0;}
    
    
    if(c<0){c=-c;    EN3=1;     INA3=0;     INB3=1;}
    else{            EN3=1;     INA3=1;     INB3=0;}
    
    if(a>500){ a=500;}
    if(b>500){ b=500;}
    if(c>500){ c=500;}
    
    
    PWM1.pulsewidth_us(a);
    PWM2.pulsewidth_us(b);   
    PWM3.pulsewidth_us(c);   
    
/*
    PWM1.pulsewidth_us(250);
    PWM2.pulsewidth_us(250); 
    PWM3.pulsewidth_us(250);
 
    wait(2);
    
    EN1=1;     INA1=1;     INB1=0;
    EN2=1;     INA2=1;     INB2=0;   
    EN3=1;     INA3=1;     INB3=0;  
    
    wait(2);
*/    
    //pc.printf("Yaw,   Pitch,   Roll,    mod,    theta,  a,  b,  c :  %f  %f  %f  %f  %f  %i  %i  %i\n\r",  yaw,   pitch,   roll, Modulo, theta,a,b,c);
    

    //--------------------------------------------------------------------------------------------------------------------------------
    //--------------------------------------------------------------------------------------------------------------------------------
    //--------------------------------------------END OF MY CODE----------------------------------------------------------------------
    //--------------------------------------------------------------------------------------------------------------------------------
    //--------------------------------------------------------------------------------------------------------------------------------
    
//}
}
 
 }