A quick and dirty demo of the Xadow M0 acceleromoeter values displayed on the Xadow OLED 0.96" (using the SSD1308 128x64 OLED Driver with I2C interface library).

Dependencies:   mbed SSD1308_128x64_I2C_opt XadowGPS BMP180 ADXL345_I2C MPU9250 USBDevice

main.cpp

Committer:
ruevs
Date:
2019-03-01
Revision:
9:310663c014d8
Parent:
8:4e8991196bb8

File content as of revision 9:310663c014d8:

#define __STDC_LIMIT_MACROS 1
#include <stdint.h>

#include "ADXL345_I2C.h"
#include "SSD1308.h"
#include "MPU9250.h"
#include "BMP180.h"

#define DEBUG

#ifdef DEBUG
#include "USBSerial.h"                       // To use USB virtual serial, a driver is needed, check http://mbed.org/handbook/USBSerial
#define LOG(args...)    pc.printf(args)
USBSerial pc;
#else
#define LOG(args...)
#endif

#define MAX_ACC_AXIS 3
ADXL345_I2C accelerometer(P0_5, P0_4);

// Xhadow - OLED 128x64 is connected with I2C
I2C i2c(P0_5, P0_4);    // SDA, SCL
SSD1308 oled = SSD1308(i2c, SSD1308_SA0);
SSD1308 oled2 = SSD1308(i2c, SSD1308_SA1);

// MPU9250 9DOF IMU - accelerometer, gyroscope, magnetometer access class
MPU9250 mpu9250(i2c);

// BMP180 pressure and temperature sensor access class
BMP180 bmp180(&i2c);

AnalogIn AD00(P0_11);
AnalogIn AD01(P0_12);
AnalogIn ChargerStatus(P0_13);      // ADC input from VCC through a 200K/200K divider with extara 100K pull down on !DONE and 49.9K on !CHRG 

DigitalOut blue_led(P0_20, 0);
DigitalOut white_led(P0_23, 1);
DigitalOut Bus3V3En(P0_14, 1);      // Pin that controls the BUS-3V3 (3.3V) regulator output to the Xadow Bus

InterruptIn test_int(P0_7);

void test_pin_int(void)
{
    white_led = !white_led;
    Bus3V3En = !Bus3V3En;
}

void MPU9250Test()
{
    Timer t;
    float sum = 0;
    uint32_t sumCount = 0;

    char buffer[14];

    uint8_t whoami;
    
  //___ Set up I2C: use fast (400 kHz) I2C ___
  i2c.frequency(400000);  
  
    wait(10); // to allow terminal to cooect on PC
  
  while(1) {
    if (bmp180.init() != 0) {
      LOG("Error communicating with BMP180r\n");
    } else {
      LOG("Initialized BMP180\r\n");
      break;
    }
    wait(1);
  }
  
  LOG("CPU SystemCoreClock is %d Hz\r\n", SystemCoreClock);
  
  t.start(); // Timer ON
  
  // Read the WHO_AM_I register, this is a good test of communication
  whoami = mpu9250.readByte(MPU9250_ADDRESS, WHO_AM_I_MPU9250);
  
  LOG("I AM 0x%x\r\n", whoami); LOG("I SHOULD BE 0x71\r\n");
  if (I2Cstate != 0) // error on I2C
    LOG("I2C failure while reading WHO_AM_I register");
  
  if (whoami == 0x71) // WHO_AM_I should always be 0x71
  {  
    LOG("MPU9250 WHO_AM_I is 0x%x\r\n", whoami);
    LOG("MPU9250 is online...\r\n");
    sprintf(buffer, "0x%x", whoami);
    wait(1);
    
    mpu9250.resetMPU9250(); // Reset registers to default in preparation for device calibration
    
    mpu9250.MPU9250SelfTest(SelfTest); // Start by performing self test and reporting values (accelerometer and gyroscope self test)
    LOG("x-axis self test: acceleration trim within : %f % of factory value\r\n", SelfTest[0]);
    LOG("y-axis self test: acceleration trim within : %f % of factory value\r\n", SelfTest[1]);
    LOG("z-axis self test: acceleration trim within : %f % of factory value\r\n", SelfTest[2]);
    LOG("x-axis self test: gyration trim within : %f % of factory value\r\n", SelfTest[3]);
    LOG("y-axis self test: gyration trim within : %f % of factory value\r\n", SelfTest[4]);
    LOG("z-axis self test: gyration trim within : %f % of factory value\r\n", SelfTest[5]);
    
    mpu9250.calibrateMPU9250(gyroBias, accelBias); // Calibrate gyro and accelerometer, load biases in bias registers  
    LOG("x gyro bias = %f\r\n", gyroBias[0]);
    LOG("y gyro bias = %f\r\n", gyroBias[1]);
    LOG("z gyro bias = %f\r\n", gyroBias[2]);
    LOG("x accel bias = %f\r\n", accelBias[0]);
    LOG("y accel bias = %f\r\n", accelBias[1]);
    LOG("z accel bias = %f\r\n", accelBias[2]);
    wait(2);
    
    // Initialize device for active mode read of acclerometer, gyroscope, and temperature
    mpu9250.initMPU9250();
    LOG("MPU9250 initialized for active data mode....\r\n");
    
    // Initialize device for active mode read of magnetometer, 16 bit resolution, 100Hz.
    mpu9250.initAK8963(magCalibration);
    LOG("AK8963 initialized for active data mode....\r\n");
    LOG("Accelerometer full-scale range = %f  g\r\n", 2.0f*(float)(1<<Ascale));
    LOG("Gyroscope full-scale range = %f  deg/s\r\n", 250.0f*(float)(1<<Gscale));
    if(Mscale == 0) LOG("Magnetometer resolution = 14  bits\r\n");
    if(Mscale == 1) LOG("Magnetometer resolution = 16  bits\r\n");
    if(Mmode == 2) LOG("Magnetometer ODR = 8 Hz\r\n");
    if(Mmode == 6) LOG("Magnetometer ODR = 100 Hz\r\n");
    wait(1);
   }
   
   else // Connection failure
   {
    LOG("Could not connect to MPU9250: \r\n");
    LOG("%#x \n",  whoami);    
    sprintf(buffer, "WHO_AM_I 0x%x", 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
    LOG("Accelerometer sensitivity is %f LSB/g \r\n", 1.0f/aRes);
    LOG("Gyroscope sensitivity is %f LSB/deg/s \r\n", 1.0f/gRes);
    LOG("Magnetometer sensitivity is %f LSB/G \r\n", 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
            if (I2Cstate != 0) //error on I2C
                LOG("I2C error ocurred while reading accelerometer data. I2Cstate = %d \r\n", I2Cstate);
            else{ // I2C read or write ok
                I2Cstate = 1;
                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
            if (I2Cstate != 0) //error on I2C
                LOG("I2C error ocurred while reading gyrometer data. I2Cstate = %d \r\n", I2Cstate);
            else{ // I2C read or write ok
                I2Cstate = 1;
                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
            if (I2Cstate != 0) //error on I2C
                LOG("I2C error ocurred while reading magnetometer data. I2Cstate = %d \r\n", I2Cstate);
            else{ // I2C read or write ok
                I2Cstate = 1;
                /* Online magnetometer calibration */
                float magAverageXYZRange = 0;
                for(int i=0;i<3;++i) {
                    if (magCount[i]<minMagCount[i]) {
                        minMagCount[i] = magCount[i];
                        magbias[i] = (minMagCount[i]+maxMagCount[i])*mRes*magCalibration[1]/2.;
                    }
                    if (magCount[i]>maxMagCount[i]) {
                        maxMagCount[i] = magCount[i];
                        magbias[i] = (minMagCount[i]+maxMagCount[i])*mRes*magCalibration[1]/2.;
                    }
                    magAverageXYZRange += maxMagCount[i]-minMagCount[i];
                }

                magAverageXYZRange /= 3.;

                for(int i=0;i<3;++i) {
                    magScale[i] = magAverageXYZRange / (maxMagCount[i]-minMagCount[i]);
                }

                mx = (float)magCount[0]*mRes*magCalibration[0]*magScale[0] - magbias[0];  // get actual magnetometer value, this depends on scale being set
                my = (float)magCount[1]*mRes*magCalibration[1]*magScale[1] - magbias[1];  
                mz = (float)magCount[2]*mRes*magCalibration[2]*magScale[2] - magbias[2];
            }
                       
            mpu9250.getCompassOrientation(orientation);
        }
   
        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++;
    
        // Sensors x (y)-axis of the accelerometer/gyro is aligned with the y (x)-axis of the magnetometer;
        // the magnetometer z-axis (+ down) is misaligned with z-axis (+ up) of accelerometer and gyro!
        // We have to make some allowance for this orientation mismatch in feeding the output to the quaternion filter.
        // We will assume that +y accel/gyro is North, then x accel/gyro is East. So if we want te quaternions properly aligned
        // we need to feed into the madgwick function Ay, Ax, -Az, Gy, Gx, -Gz, Mx, My, and Mz. But because gravity is by convention
        // positive down, we need to invert the accel data, so we pass -Ay, -Ax, Az, Gy, Gx, -Gz, Mx, My, and Mz into the Madgwick
        // function to get North along the accel +y-axis, East along the accel +x-axis, and Down along the accel -z-axis.
        // This orientation choice can be modified to allow any convenient (non-NED) orientation convention.
        // This is ok by aircraft orientation standards!  
        // Pass gyro rate as rad/s
        // mpu9250.MadgwickQuaternionUpdate(-ay, -ax, az, gy*PI/180.0f, gx*PI/180.0f, -gz*PI/180.0f,  mx,  my, mz);
        mpu9250.MahonyQuaternionUpdate(-ay, -ax, az, gy*PI/180.0f, gx*PI/180.0f, -gz*PI/180.0f, mx, my, mz);

        white_led= !white_led;

        // Serial print and/or display at 1.5 s rate independent of data rates
        delt_t = t.read_ms() - count;
        if (delt_t > 1500) { // update LCD once per half-second independent of read rate
            LOG("\033[2J");        // ANSI clear screen ESC[2J
            LOG("ax = %f", 1000*ax);
            LOG(" ay = %f", 1000*ay);
            LOG(" az = %f  mg\r\n", 1000*az);
            LOG("gx = %f", gx);
            LOG(" gy = %f", gy);
            LOG(" gz = %f  deg/s\r\n", gz);
            LOG("mx = %f", mx); 
            LOG(" my = %f", my); 
            LOG(" mz = %f  mG\r\n", mz);
            LOG("minmx = %i", minMagCount[0]); 
            LOG(" minmy = %i", minMagCount[1]); 
            LOG(" minmz = %i\r\n", minMagCount[2]);
            LOG("maxmx = %i", maxMagCount[0]); 
            LOG(" maxmy = %i", maxMagCount[1]); 
            LOG(" maxmz = %i\r\n", maxMagCount[2]);
            LOG("magbiasx = %f", magbias[0]); 
            LOG(" magbiasy = %f", magbias[1]); 
            LOG(" magbiasz = %f mG\r\n", magbias[2]);
            LOG("magscalex = %f", magScale[0]); 
            LOG(" magscaley = %f", magScale[1]); 
            LOG(" magscalez = %f mG\r\n", magScale[2]);
            

            tempCount = mpu9250.readTempData();  // Read the adc values
            if (I2Cstate != 0) //error on I2C
                LOG("I2C error ocurred while reading sensor temp. I2Cstate = %d \r\n", I2Cstate);
            else{ // I2C read or write ok                
                I2Cstate = 1;
                temperature = ((float) tempCount) / 333.87f + 21.0f; // Temperature in degrees Centigrade
                LOG(" temperature = %f  C\r\n", temperature);
            }
            LOG("q0 = %f\r\n", q[0]);
            LOG("q1 = %f\r\n", q[1]);
            LOG("q2 = %f\r\n", q[2]);
            LOG("q3 = %f\r\n", q[3]);
            
            LOG("Compass orientation: %f\r\n", orientation[0]);
    
            
            
            
            // 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;

            
            LOG("Yaw, Pitch, Roll: %f %f %f\r\n", yaw, pitch, roll);
            LOG("average rate = %f\r\n", (float) sumCount/sum);
            
            
    
            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();
            }
        sum = 0;
        sumCount = 0; 

    //BMP180        
            bmp180.startTemperature();
            wait_ms(5);     // Wait for conversion to complete
            float temp;
            if(bmp180.getTemperature(&temp) != 0) {
                LOG("Error getting temperature\n");
                continue;
            }
     
            bmp180.startPressure(BMP180::ULTRA_LOW_POWER);
            wait_ms(10);    // Wait for conversion to complete
            int pressure;
            if(bmp180.getPressure(&pressure) != 0) {
                LOG("Error getting pressure\n");
                continue;
            }
     
            LOG("Pressure = %d Pa Temperature = %f C\r\n", pressure, temp);

        }
    }
}

int main()
{
    int readings[MAX_ACC_AXIS] = {0, 0, 0};
    int MAXreadings[MAX_ACC_AXIS] = {INT16_MIN, INT16_MIN, INT16_MIN};
    int MINreadings[MAX_ACC_AXIS] = {INT16_MAX, INT16_MAX, INT16_MAX};

    char display_buf[17];
    
    test_int.rise(test_pin_int);

    MPU9250Test();

    LOG("Starting ADXL345 test...\n");
    LOG("Device ID is: 0x%02x\n", accelerometer.getDeviceID());

/* // Simple OLED speed test
    oled.fillDisplay(0xAA);
    oled.writeBigChar(1,0,'6');

    uint8_t cnt=0;
    int cycl=0;
    while(1){
        snprintf(display_buf, sizeof(display_buf), "%5i", cnt++);
        oled.writeString(0, 0, display_buf);
        if (0==cnt) {
            ++cycl;
            snprintf(display_buf, sizeof(display_buf), "%5i", cycl);
            oled.writeString(1, 0, display_buf);
        }
    }
*/
    oled2.writeString(0, 0, "OLED 2:");
    oled2.writeString(1, 0, "GEEKCREIT");
    oled2.writeString(2, 0, "Banggood 0x7A");

    oled.writeString(0, 0, "Accelerometer:");
    oled.writeString(1, 0, "  Curr  Min  Max");
 
    //Go into standby mode to configure the device.
    accelerometer.setPowerControl(0x00);
 
    //Full resolution, +/-16g, 4mg/LSB.
    accelerometer.setDataFormatControl(0x0B);
     
    //3.2kHz data rate.
    accelerometer.setDataRate(ADXL345_3200HZ);
 
    //Measurement mode.
    accelerometer.setPowerControl(0x08);

    while (1) {
        accelerometer.getOutput(readings);
        
        for (int i=0; i<MAX_ACC_AXIS; ++i) {
            if ((int16_t)readings[i] > (int16_t)MAXreadings[i]) {
                MAXreadings[i] = readings[i];    
            }
            if ((int16_t)readings[i] < (int16_t)MINreadings[i]) {
                MINreadings[i] = readings[i];    
            }
            
            snprintf(display_buf, sizeof(display_buf), "%c%5i%5i%5i",
                     'X'+i, (int16_t)readings[i], (int16_t)MINreadings[i], (int16_t)MAXreadings[i] );
            oled.writeString(2+i, 0, display_buf);
            LOG("%c:%i|%i|%i\r\n", 'X'+i, (int16_t)readings[i], (int16_t)MINreadings[i], (int16_t)MAXreadings[i] );
        }
        
/*        snprintf(display_buf, sizeof(display_buf), "Ch: %u", ChargerStatus.read_u16());
        oled.writeString(2+MAX_ACC_AXIS, 0, display_buf);

        snprintf(display_buf, sizeof(display_buf), "Ch: %f", 3.3*(float)ChargerStatus.read_u16()/UINT16_MAX);
        oled.writeString(2+MAX_ACC_AXIS+1, 0, display_buf);
*/        
        snprintf(display_buf, sizeof(display_buf), "Bat:%.2fV", 3.3*ChargerStatus);
        oled.writeString(2+MAX_ACC_AXIS+2, 0, display_buf);
        
        LOG("Ch: %f\r\n", ChargerStatus.read());
        LOG("Chu: %u\r\n", ChargerStatus.read_u16());
        LOG("A0: %f\r\n", (float)AD00.read());
        LOG("A1: %f\r\n", AD01.read());
        
        blue_led = !blue_led;
 //       white_led = !white_led;   // toggled by pin P0_7 interrupt
 
//        deepsleep();  // Deep sleep until external interrupt  // The wakeup pin on Xadow is on the sme buton at RESET - no good.
        
        wait(1);
    }

}