SkipperS2v2 and bmp
Dependencies: BMP280 mpu9250forskipper mbed
main.cpp
- Committer:
- motoseki
- Date:
- 2016-08-15
- Revision:
- 1:5c8e961811d1
- Parent:
- 0:e6b1cd3646df
- Child:
- 2:c1c7afb86416
File content as of revision 1:5c8e961811d1:
#include "mbed.h" #include "MPU9250.h" #include "BMP280.h" #define bmpadr 0x76<<1 // SD0 pulldown 0x76<<1 , pullup 0x77<<1 //I2C SDA,SCL: PC_9, PA_8 SPI spi(PC_12, PC_11, PC_10); // mosi, miso, sclk DigitalOut cs(PA_15); Serial pc(PA_2,PA_3); //v2 //Serial pc(PA_9,PA_10); //original float sum = 0; uint32_t sumCount = 0; MPU9250 mpu9250; BMP280 bmp(PC_9, PA_8 ,bmpadr); //(PinName sda, PinName scl, char slave_adr) Timer t; int main() { wait(2); pc.baud(9600); //a8=0; //c9=0; pc.printf("SkipperS2 Peripheral Test...\n");wait(1); pc.printf("L2G2IS SPI 0xD9?\n"); // Chip must be deselected cs = 1; // Setup the spi for 8 bit data, high steady state clock, // second edge capture, with a 1MHz clock rate spi.format(8,3); spi.frequency(1000000); // Select the device by seting chip select low cs = 0; // Send 0x8f, the command to read the WHOAMI register spi.write(0x80); // Send a dummy byte to receive the contents of the WHOAMI register int whoami_l2 = spi.write(0x00); pc.printf("WHOAMI register = 0x%X\n", whoami_l2); // Deselect the device cs = 1; pc.printf("MPU9250 I2C test\n"); //Set up I2C i2c.frequency(400000); // use fast (400 kHz) I2C pc.printf("CPU SystemCoreClock is %d Hz\r\n", SystemCoreClock); t.start(); //BMP initialize bmp.initialize(); while(1){ pc.printf("TEM : %f, PRE : %f\n",bmp.getTemperature(),bmp.getPressure()); wait_ms(500); } // 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 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 > 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); //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; } } while(1){ pc.printf("."); wait(1); } }