航空研究会 / MPU9255

Files at this revision

API Documentation at this revision

Comitter:
imanomadao
Date:
Sun Jun 28 11:10:43 2020 +0000
Commit message:
a;

Changed in this revision

MPU9255.cpp Show annotated file Show diff for this revision Revisions of this file
MPU9255.h Show annotated file Show diff for this revision Revisions of this file
MPU9255Regs.h Show annotated file Show diff for this revision Revisions of this file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MPU9255.cpp	Sun Jun 28 11:10:43 2020 +0000
@@ -0,0 +1,532 @@
+#include"MPU9255.h"
+
+//-----------------
+//private functions
+//-----------------
+
+void MPU9255::writeByte(uint8_t address, uint8_t subAddress, uint8_t data)
+{
+   char data_write[2];
+   data_write[0] = subAddress;
+   data_write[1] = data;
+   i2c.write(address, data_write, 2, 0);
+}
+
+char MPU9255::readByte(uint8_t address, uint8_t subAddress)
+{
+    char data[1]; // `data` will store the register data     
+    char data_write[1];
+    data_write[0] = subAddress;
+    i2c.write(address, data_write, 1, 1); // no stop
+    i2c.read(address, data, 1, 0); 
+    return data[0]; 
+}
+
+void MPU9255::readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest)
+{     
+    char data[14];
+    char data_write[1];
+    data_write[0] = subAddress;
+    i2c.write(address, data_write, 1, 1); // no stop
+    i2c.read(address, data, count, 0); 
+    for(int ii = 0; ii < count; ii++) 
+    {
+        dest[ii] = data[ii];
+    }
+} 
+
+
+//----------------
+//public functions
+//----------------
+
+MPU9255::MPU9255(PinName sda, PinName scl, RawSerial* serial_p)
+    : i2c_p(new I2C(sda,scl)), i2c(*i2c_p), pc_p(serial_p)
+{
+    i2c.frequency(40000);
+}
+
+MPU9255::~MPU9255() {}
+
+uint8_t MPU9255::whoami_mpu9255()
+{
+    uint8_t a = readByte(MPU9255_ADDRESS, WHO_AM_I_MPU9255);
+    return a;
+}
+
+void MPU9255::reset_mpu9255()
+{
+    writeByte(MPU9255_ADDRESS, PWR_MGMT_1, 0x80);
+    wait_ms(10);
+}
+
+void MPU9255::selftest_mpu9255(float * destination) // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass
+{
+    uint8_t rawData[6] = {0, 0, 0, 0, 0, 0};
+    uint8_t selfTest[6];
+    int32_t gAvg[3] = {0}, aAvg[3] = {0}, aSTAvg[3] = {0}, gSTAvg[3] = {0};
+    float factoryTrim[6];
+    uint8_t FS = 0;
+   
+    writeByte(MPU9255_ADDRESS, SMPLRT_DIV, 0x00);    // Set gyro sample rate to 1 kHz
+    writeByte(MPU9255_ADDRESS, CONFIG, 0x02);        // Set gyro sample rate to 1 kHz and DLPF to 92 Hz
+    writeByte(MPU9255_ADDRESS, GYRO_CONFIG, 1<<FS);  // Set full scale range for the gyro to 250 dps
+    writeByte(MPU9255_ADDRESS, ACCEL_CONFIG2, 0x02); // Set accelerometer rate to 1 kHz and bandwidth to 92 Hz
+    writeByte(MPU9255_ADDRESS, ACCEL_CONFIG, 1<<FS); // Set full scale range for the accelerometer to 2 g      
+
+    for( int ii = 0; ii < 200; ii++)   // get average current values of gyro and acclerometer
+    {  
+        readBytes(MPU9255_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]);        // Read the six raw data registers into data array
+        aAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ;  // Turn the MSB and LSB into a signed 16-bit value
+        aAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;  
+        aAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 
+  
+        readBytes(MPU9255_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]);       // Read the six raw data registers sequentially into data array
+        gAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ;  // Turn the MSB and LSB into a signed 16-bit value
+        gAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;  
+        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
+    {
+        aAvg[ii] /= 200;
+        gAvg[ii] /= 200;
+    }
+  
+// Configure the accelerometer for self-test
+    writeByte(MPU9255_ADDRESS, ACCEL_CONFIG, 0xE0); // Enable self test on all three axes and set accelerometer range to +/- 2 g
+    writeByte(MPU9255_ADDRESS, GYRO_CONFIG,  0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s
+    wait_ms(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
+    {
+        readBytes(MPU9255_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(MPU9255_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
+    {
+        aSTAvg[ii] /= 200;
+        gSTAvg[ii] /= 200;
+    }   
+  
+ // Configure the gyro and accelerometer for normal operation
+    writeByte(MPU9255_ADDRESS, ACCEL_CONFIG, 0x00);  
+    writeByte(MPU9255_ADDRESS, GYRO_CONFIG,  0x00);  
+    wait_ms(25);  // Delay a while to let the device stabilize
+   
+   // Retrieve accelerometer and gyro factory Self-Test Code from USR_Reg
+    selfTest[0] = readByte(MPU9255_ADDRESS, SELF_TEST_X_ACCEL); // X-axis accel self-test results
+    selfTest[1] = readByte(MPU9255_ADDRESS, SELF_TEST_Y_ACCEL); // Y-axis accel self-test results
+    selfTest[2] = readByte(MPU9255_ADDRESS, SELF_TEST_Z_ACCEL); // Z-axis accel self-test results
+    selfTest[3] = readByte(MPU9255_ADDRESS, SELF_TEST_X_GYRO);  // X-axis gyro self-test results
+    selfTest[4] = readByte(MPU9255_ADDRESS, SELF_TEST_Y_GYRO);  // Y-axis gyro self-test results
+    selfTest[5] = readByte(MPU9255_ADDRESS, SELF_TEST_Z_GYRO);  // Z-axis gyro self-test results
+
+  // Retrieve factory self-test value from self-test code reads
+    factoryTrim[0] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[0] - 1.0) )); // FT[Xa] factory trim calculation
+    factoryTrim[1] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[1] - 1.0) )); // FT[Ya] factory trim calculation
+    factoryTrim[2] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[2] - 1.0) )); // FT[Za] factory trim calculation
+    factoryTrim[3] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[3] - 1.0) )); // FT[Xg] factory trim calculation
+    factoryTrim[4] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[4] - 1.0) )); // FT[Yg] factory trim calculation
+    factoryTrim[5] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[5] - 1.0) )); // FT[Zg] factory trim calculation
+ 
+ // 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++) 
+    {
+        destination[i]   = 100.0f*((float)(aSTAvg[i] - aAvg[i]))/factoryTrim[i] - 100.0f;   // Report percent differences
+        destination[i+3] = 100.0f*((float)(gSTAvg[i] - gAvg[i]))/factoryTrim[i+3] - 100.0f; // Report percent differences
+    }
+   
+}
+
+float MPU9255::getMres(uint8_t Mscale) 
+{
+    float _mRes;
+    switch (Mscale)
+    {
+   // Possible magnetometer scales (and their register bit settings) are:
+  // 14 bit resolution (0) and 16 bit resolution (1)
+        case MFS_14BITS:
+            _mRes = 10.*4912./8190.; // Proper scale to return milliGauss
+            return _mRes;
+            //break;
+        case MFS_16BITS:
+            _mRes = 10.*4912./32760.0; // Proper scale to return milliGauss (4912/32760=0.15)
+            return _mRes;              // convert 'μT' to 'mG' 
+            //break;
+    }
+}
+
+float MPU9255::getGres(uint8_t Gscale)
+{
+    float _gRes;
+    switch (Gscale)
+    {
+  // Possible gyro scales (and their register bit settings) are:
+  // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS  (11). 
+        case GFS_250DPS:
+            _gRes = 250.0/32768.0;
+            return _gRes;
+            //break;
+        case GFS_500DPS:
+            _gRes = 500.0/32768.0;
+            return _gRes;
+            //break;
+        case GFS_1000DPS:
+            _gRes = 1000.0/32768.0;
+            return _gRes;
+            //break;
+        case GFS_2000DPS:
+            _gRes = 2000.0/32768.0;
+            return _gRes;
+            //break;
+    }
+}
+
+float MPU9255::getAres(uint8_t Ascale)
+{
+    float _aRes;
+    switch (Ascale)
+    {
+  // Possible accelerometer scales (and their register bit settings) are:
+  // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs  (11). 
+        // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value:
+        case AFS_2G:
+            _aRes = 2.0f/32768.0f;
+            return _aRes;
+            //break;
+        case AFS_4G:
+            _aRes = 4.0f/32768.0f;
+            return _aRes;
+            //break;
+        case AFS_8G:
+            _aRes = 8.0f/32768.0f;
+            return _aRes;
+            //break;
+        case AFS_16G:
+            _aRes = 16.0f/32768.0f;
+            return _aRes;
+            //break;
+    }
+}
+
+void MPU9255::calibrate_mpu9255(float * dest1, float * dest2)
+{  
+    uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data
+    uint16_t ii, packet_count, fifo_count;
+    int32_t gyro_bias[3]  = {0, 0, 0}, accel_bias[3] = {0, 0, 0};
+  
+    // reset device
+    writeByte(MPU9255_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
+    wait_ms(100);
+   
+    // get stable time source; Auto select clock source to be PLL gyroscope reference if ready 
+    // else use the internal oscillator, bits 2:0 = 001
+    writeByte(MPU9255_ADDRESS, PWR_MGMT_1, 0x01);  
+    writeByte(MPU9255_ADDRESS, PWR_MGMT_2, 0x00);
+    wait_ms(200);                                    
+
+    // Configure device for bias calculation
+    writeByte(MPU9255_ADDRESS, INT_ENABLE, 0x00);   // Disable all interrupts
+    writeByte(MPU9255_ADDRESS, FIFO_EN, 0x00);      // Disable FIFO
+    writeByte(MPU9255_ADDRESS, PWR_MGMT_1, 0x00);   // Turn on internal clock source
+    writeByte(MPU9255_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master
+    writeByte(MPU9255_ADDRESS, USER_CTRL, 0x00);    // Disable FIFO and I2C master modes
+    writeByte(MPU9255_ADDRESS, USER_CTRL, 0x0C);    // Reset FIFO and DMP
+    wait_ms(15);
+  
+    // Configure MPU6050 gyro and accelerometer for bias calculation
+    writeByte(MPU9255_ADDRESS, CONFIG, 0x01);      // Set low-pass filter to 188 Hz
+    writeByte(MPU9255_ADDRESS, SMPLRT_DIV, 0x00);  // Set sample rate to 1 kHz
+    writeByte(MPU9255_ADDRESS, GYRO_CONFIG, 0x00);  // Set gyro full-scale to 250 degrees per second, maximum sensitivity
+    writeByte(MPU9255_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity
+ 
+    uint16_t  gyrosensitivity  = 131;   // = 131 LSB/degrees/sec
+    uint16_t  accelsensitivity = 16384;  // = 16384 LSB/g
+
+    // Configure FIFO to capture accelerometer and gyro data for bias calculation
+    writeByte(MPU9255_ADDRESS, USER_CTRL, 0x40);   // Enable FIFO  
+    writeByte(MPU9255_ADDRESS, FIFO_EN, 0x78);     // Enable gyro and accelerometer sensors for FIFO  (max size 512 bytes in MPU-9150)
+    wait_ms(40); // accumulate 40 samples in 40 milliseconds = 480 bytes
+
+// At end of sample accumulation, turn off FIFO sensor read
+    writeByte(MPU9255_ADDRESS, FIFO_EN, 0x00);        // Disable gyro and accelerometer sensors for FIFO
+    readBytes(MPU9255_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count
+    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++) 
+    {
+        int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0};
+        readBytes(MPU9255_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
+        accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3]  ) ;
+        accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5]  ) ;    
+        gyro_temp[0]  = (int16_t) (((int16_t)data[6] << 8) | data[7]  ) ;
+        gyro_temp[1]  = (int16_t) (((int16_t)data[8] << 8) | data[9]  ) ;
+        gyro_temp[2]  = (int16_t) (((int16_t)data[10] << 8) | data[11]) ;
+    
+        accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases
+        accel_bias[1] += (int32_t) accel_temp[1];
+        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];
+            
+    }
+        
+    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;
+    gyro_bias[0]  /= (int32_t) packet_count;
+    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;}
+   
+// 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(MPU9255_ADDRESS, XG_OFFSET_H, data[0]);
+    writeByte(MPU9255_ADDRESS, XG_OFFSET_L, data[1]);
+    writeByte(MPU9255_ADDRESS, YG_OFFSET_H, data[2]);
+    writeByte(MPU9255_ADDRESS, YG_OFFSET_L, data[3]);
+    writeByte(MPU9255_ADDRESS, ZG_OFFSET_H, data[4]);
+    writeByte(MPU9255_ADDRESS, ZG_OFFSET_L, data[5]);
+  
+// Output scaled gyro biases for display in the main program
+    dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity;  
+    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
+// non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature
+// 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(MPU9255_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values
+    accel_bias_reg[0] = (int32_t) (((int16_t)data[0] << 8) | data[1]);
+    readBytes(MPU9255_ADDRESS, YA_OFFSET_H, 2, &data[0]);
+    accel_bias_reg[1] = (int32_t) (((int16_t)data[0] << 8) | data[1]);
+    readBytes(MPU9255_ADDRESS, ZA_OFFSET_H, 2, &data[0]);
+    accel_bias_reg[2] = (int32_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
+  
+    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);
+  
+    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-9255
+// Are we handling the temperature correction bit properly?
+// Push accelerometer biases to hardware registers
+//  writeByte(MPU9255_ADDRESS, XA_OFFSET_H, data[0]);
+//  writeByte(MPU9255_ADDRESS, XA_OFFSET_L, data[1]);
+//  writeByte(MPU9255_ADDRESS, YA_OFFSET_H, data[2]);
+//  writeByte(MPU9255_ADDRESS, YA_OFFSET_L, data[3]);
+//  writeByte(MPU9255_ADDRESS, ZA_OFFSET_H, data[4]);
+//  writeByte(MPU9255_ADDRESS, ZA_OFFSET_L, data[5]);
+
+// Output scaled accelerometer biases for display in the main program
+    dest2[0] = (float)accel_bias[0]/(float)accelsensitivity; 
+    dest2[1] = (float)accel_bias[1]/(float)accelsensitivity;
+    dest2[2] = (float)accel_bias[2]/(float)accelsensitivity;
+}
+
+void MPU9255::init_mpu9255(uint8_t Ascale, uint8_t Gscale, uint8_t sampleRate)
+{  
+ // wake up device
+    writeByte(MPU9255_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors 
+    wait_ms(100); // Wait for all registers to reset 
+
+ // get stable time source
+    writeByte(MPU9255_ADDRESS, PWR_MGMT_1, 0x01);  // Auto select clock source to be PLL gyroscope reference if ready else
+    wait_ms(200); 
+  
+ // Configure Gyro and Thermometer
+ // Disable FSYNC and set thermometer and gyro bandwidth to 41 and 42 Hz, respectively; 
+ // minimum delay time for this setting is 5.9 ms, which means sensor fusion update rates cannot
+ // be higher than 1 / 0.0059 = 170 Hz
+ // DLPF_CFG = bits 2:0 = 011; this limits the sample rate to 1000 Hz for both
+ // With the MPU9255, it is possible to get gyro sample rates of 32 kHz (!), 8 kHz, or 1 kHz
+    writeByte(MPU9255_ADDRESS, CONFIG, 0x03);  
+
+ // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV)
+    writeByte(MPU9255_ADDRESS, SMPLRT_DIV, sampleRate);  // Use a 200 Hz rate; a rate consistent with the filter update rate 
+                                                       // determined inset in CONFIG above
+ 
+ // Set gyroscope full scale range
+ // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3
+    uint8_t c = readByte(MPU9255_ADDRESS, GYRO_CONFIG); // get current GYRO_CONFIG register value
+ // c = c & ~0xE0; // Clear self-test bits [7:5] 
+    c = c & ~0x02; // Clear Fchoice bits [1:0] 
+    c = c & ~0x18; // Clear AFS bits [4:3]
+    c = c | Gscale << 3; // Set full scale range for the gyro
+ // c =| 0x00; // Set Fchoice for the gyro to 11 by writing its inverse to bits 1:0 of GYRO_CONFIG
+    writeByte(MPU9255_ADDRESS, GYRO_CONFIG, c ); // Write new GYRO_CONFIG value to register
+  
+ // Set accelerometer full-scale range configuration
+    c = readByte(MPU9255_ADDRESS, ACCEL_CONFIG); // get current ACCEL_CONFIG register value
+ // c = c & ~0xE0; // Clear self-test bits [7:5] 
+    c = c & ~0x18;  // Clear AFS bits [4:3]
+    c = c | Ascale << 3; // Set full scale range for the accelerometer 
+    writeByte(MPU9255_ADDRESS, ACCEL_CONFIG, c); // Write new ACCEL_CONFIG register value
+
+ // Set accelerometer sample rate configuration
+ // 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(MPU9255_ADDRESS, ACCEL_CONFIG2); // get current ACCEL_CONFIG2 register value
+    c = c & ~0x0F; // Clear accel_fchoice_b (bit 3) and A_DLPFG (bits [2:0])  
+    c = c | 0x03;  // Set accelerometer rate to 1 kHz and bandwidth to 41 Hz
+    writeByte(MPU9255_ADDRESS, ACCEL_CONFIG2, c); // Write new ACCEL_CONFIG2 register value
+
+ // The accelerometer, gyro, and thermometer are set to 1 kHz sample rates, 
+ // but all these rates are further reduced by a factor of 5 to 200 Hz because of the SMPLRT_DIV setting
+
+  // Configure Interrupts and Bypass Enable
+  // Set interrupt pin active high, push-pull, hold interrupt pin level HIGH until interrupt cleared,
+  // clear on read of INT_STATUS, and enable I2C_BYPASS_EN so additional chips 
+  // can join the I2C bus and all can be controlled by the Arduino as master
+    writeByte(MPU9255_ADDRESS, INT_PIN_CFG, 0x10);  // INT is 50 microsecond pulse and any read to clear  
+    writeByte(MPU9255_ADDRESS, INT_ENABLE, 0x01);  // Enable data ready (bit 0) interrupt
+    wait_ms(100);
+ 
+    writeByte(MPU9255_ADDRESS, USER_CTRL, 0x20);          // Enable I2C Master mode  
+    writeByte(MPU9255_ADDRESS, I2C_MST_CTRL, 0x1D);       // I2C configuration STOP after each transaction, master I2C bus at 400 KHz
+    writeByte(MPU9255_ADDRESS, I2C_MST_DELAY_CTRL, 0x81); // Use blocking data retreival and enable delay for mag sample rate mismatch
+    writeByte(MPU9255_ADDRESS, I2C_SLV4_CTRL, 0x01);      // Delay mag data retrieval to once every other accel/gyro data sample
+}
+
+
+uint8_t MPU9255::get_AK8963CID()
+{
+    writeByte(MPU9255_ADDRESS, USER_CTRL, 0x20);    // Enable I2C Master mode  
+    writeByte(MPU9255_ADDRESS, I2C_MST_CTRL, 0x0D); // I2C configuration multi-master I2C 400KHz
+
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_ADDR, AK8963_ADDRESS | 0x80);    // Set the I2C slave address of AK8963 and set for read.
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_REG, WHO_AM_I_AK8963);           // I2C slave 0 register address from where to begin data transfer
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_CTRL, 0x81);                     // Enable I2C and transfer 1 byte
+    wait_ms(10);
+    uint8_t c = readByte(MPU9255_ADDRESS, EXT_SENS_DATA_00);             // Read the WHO_AM_I byte
+    return c;
+}
+
+void MPU9255::init_AK8963Slave(uint8_t Mscale, uint8_t Mmode, float * magCalibration)
+{
+   // First extract the factory calibration for each magnetometer axis
+    uint8_t rawData[3];  // x/y/z gyro calibration data stored here
+
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_ADDR, AK8963_ADDRESS);           // Set the I2C slave address of AK8963 and set for write.
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_REG, AK8963_CNTL2);              // I2C slave 0 register address from where to begin data transfer
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_DO, 0x01);                       // Reset AK8963
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_CTRL, 0x81);                     // Enable I2C and write 1 byte
+    wait_ms(50);
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_ADDR, AK8963_ADDRESS);           // Set the I2C slave address of AK8963 and set for write.
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_REG, AK8963_CNTL);               // I2C slave 0 register address from where to begin data transfer
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_DO, 0x00);                       // Power down magnetometer  
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_CTRL, 0x81);                     // Enable I2C and write 1 byte
+    wait_ms(50);
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_ADDR, AK8963_ADDRESS);           // Set the I2C slave address of AK8963 and set for write.
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_REG, AK8963_CNTL);               // I2C slave 0 register address from where to begin data transfer
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_DO, 0x0F);                       // Enter fuze mode
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_CTRL, 0x81);                     // Enable I2C and write 1 byte
+    wait_ms(50);
+   
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_ADDR, AK8963_ADDRESS | 0x80);    // Set the I2C slave address of AK8963 and set for read.
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_REG, AK8963_ASAX);               // I2C slave 0 register address from where to begin data transfer
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_CTRL, 0x83);                     // Enable I2C and read 3 bytes
+    wait_ms(50);
+    readBytes(MPU9255_ADDRESS, EXT_SENS_DATA_00, 3, &rawData[0]);        // Read the x-, y-, and z-axis calibration values
+    magCalibration[0] =  (float)(rawData[0] - 128)/256.0f + 1.0f;        // Return x-axis sensitivity adjustment values, etc.
+    magCalibration[1] =  (float)(rawData[1] - 128)/256.0f + 1.0f;  
+    magCalibration[2] =  (float)(rawData[2] - 128)/256.0f + 1.0f; 
+    /*_magCalibration[0] = magCalibration[0];
+    _magCalibration[1] = magCalibration[1];
+    _magCalibration[2] = magCalibration[2];
+    _Mmode = Mmode;*/
+    
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_ADDR, AK8963_ADDRESS);           // Set the I2C slave address of AK8963 and set for write.
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_REG, AK8963_CNTL);               // I2C slave 0 register address from where to begin data transfer
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_DO, 0x00);                       // Power down magnetometer  
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_CTRL, 0x81);                     // Enable I2C and transfer 1 byte
+    wait_ms(50);
+
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_ADDR, AK8963_ADDRESS);           // Set the I2C slave address of AK8963 and set for write.
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_REG, AK8963_CNTL);               // I2C slave 0 register address from where to begin data transfer 
+    // Configure the magnetometer for continuous read and highest resolution
+   // set Mscale bit 4 to 1 (0) to enable 16 (14) bit resolution in CNTL register,
+   // and enable continuous mode data acquisition Mmode (bits [3:0]), 0010 for 8 Hz and 0110 for 100 Hz sample rates
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_DO, Mscale << 4 | Mmode);        // Set magnetometer data resolution and sample ODR
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_CTRL, 0x81);                     // Enable I2C and transfer 1 byte
+    wait_ms(50);
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_ADDR, AK8963_ADDRESS | 0x80);    // Set the I2C slave address of AK8963 and set for read.
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_REG, AK8963_CNTL);               // I2C slave 0 register address from where to begin data transfer
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_CTRL, 0x81);                     // Enable I2C and transfer 1 byte
+    wait_ms(50);
+}
+
+void MPU9255::readMagData_mpu9255(int16_t * destination)
+{
+    uint8_t rawData[7];  // x/y/z gyro register data, ST2 register stored here, must read ST2 at end of data acquisition
+//  readBytes(AK8963_ADDRESS, AK8963_XOUT_L, 7, &rawData[0]);  // Read the six raw data and ST2 registers sequentially into data array
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_ADDR, AK8963_ADDRESS | 0x80);    // Set the I2C slave address of AK8963 and set for read.
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_REG, AK8963_XOUT_L);             // I2C slave 0 register address from where to begin data transfer
+    writeByte(MPU9255_ADDRESS, I2C_SLV0_CTRL, 0x87);                     // Enable I2C and read 7 bytes
+    wait_ms(2);
+    readBytes(MPU9255_ADDRESS, EXT_SENS_DATA_00, 7, &rawData[0]);        // Read the x-, y-, and z-axis calibration values
+    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
+    {
+        destination[0] = ((int16_t)rawData[1] << 8) | rawData[0] ;  // Turn the MSB and LSB into a signed 16-bit value
+        destination[1] = ((int16_t)rawData[3] << 8) | rawData[2] ;  // Data stored as little Endian
+        destination[2] = ((int16_t)rawData[5] << 8) | rawData[4] ; 
+    }
+}
+
+void MPU9255::readaccgyrodata_mpu9255(int16_t * destination)
+{
+    uint8_t rawData[14];  // x/y/z accel register data stored here
+    readBytes(MPU9255_ADDRESS, ACCEL_XOUT_H, 14, &rawData[0]);  // Read the 14 raw data registers into data array
+    destination[0] = ((int16_t)rawData[0] << 8) | rawData[1] ;  // Turn the MSB and LSB into a signed 16-bit value
+    destination[1] = ((int16_t)rawData[2] << 8) | rawData[3] ;  
+    destination[2] = ((int16_t)rawData[4] << 8) | rawData[5] ; 
+    destination[3] = ((int16_t)rawData[6] << 8) | rawData[7] ;   
+    destination[4] = ((int16_t)rawData[8] << 8) | rawData[9] ;  
+    destination[5] = ((int16_t)rawData[10] << 8) | rawData[11] ;  
+    destination[6] = ((int16_t)rawData[12] << 8) | rawData[13] ; 
+}
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MPU9255.h	Sun Jun 28 11:10:43 2020 +0000
@@ -0,0 +1,53 @@
+#ifndef _MPU9255_H_
+#define _MPU9255_H_
+
+#include"mbed.h"
+#include"MPU9255Regs.h"
+
+// Set initial input parameters
+#define  AFS_2G  0
+#define  AFS_4G  1
+#define  AFS_8G  2
+#define  AFS_16G 3
+
+#define  GFS_250DPS  0
+#define  GFS_500DPS  1
+#define  GFS_1000DPS 2
+#define  GFS_2000DPS 3
+
+#define  MFS_14BITS  0 // 0.6 mG per LSB
+#define  MFS_16BITS  1    // 0.15 mG per LSB
+
+#define M_8Hz   0x02
+#define M_100Hz 0x06
+
+
+class MPU9255
+{
+    I2C *i2c_p;
+    I2C &i2c;
+    RawSerial* pc_p;
+    
+    void writeByte(uint8_t address, uint8_t subAddress, uint8_t data);
+    char readByte(uint8_t address, uint8_t subAddress);
+    void readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest);
+
+public:
+    MPU9255(PinName sda, PinName scl, RawSerial* serial_p);
+    ~MPU9255();
+    
+    void init_mpu9255(uint8_t Ascale, uint8_t Cscale, uint8_t asmpleRate);
+    uint8_t whoami_mpu9255();
+    void reset_mpu9255();
+    void selftest_mpu9255(float * destination);
+    float getAres(uint8_t Ascale);
+    float getGres(uint8_t Gscale);
+    float getMres(uint8_t Mscale);
+    void calibrate_mpu9255(float * dest1, float * dest2);
+    uint8_t get_AK8963CID();
+    void init_AK8963Slave(uint8_t Mscale, uint8_t Mmode, float * magCalibration);
+    void readMagData_mpu9255(int16_t * destination);
+    void readaccgyrodata_mpu9255(int16_t * destination);
+};
+
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MPU9255Regs.h	Sun Jun 28 11:10:43 2020 +0000
@@ -0,0 +1,154 @@
+#ifndef MPU9250_REGISTER_H
+#define MPU9250_REGISTER_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
+
+//AK8963 registers
+#define AK8963_ADDRESS   0x0C // used in slave mode, ak8963c's adress is 0x0c
+#define WHO_AM_I_AK8963  0x00 // should return 0x48
+#define INFO             0x01
+#define AK8963_ST1       0x02  // data ready status bit 0
+#define AK8963_XOUT_L    0x03  // data
+#define AK8963_XOUT_H    0x04
+#define AK8963_YOUT_L    0x05
+#define AK8963_YOUT_H    0x06
+#define AK8963_ZOUT_L    0x07
+#define AK8963_ZOUT_H    0x08
+#define AK8963_ST2       0x09  // Data overflow bit 3 and data read error status bit 2
+#define AK8963_CNTL      0x0A  // Power down (0000), single-measurement (0001), self-test (1000) and Fuse ROM (1111) modes on bits 3:0
+#define AK8963_CNTL2     0x0B  // Reset
+#define AK8963_ASTC      0x0C  // Self test control
+#define AK8963_I2CDIS    0x0F  // I2C disable
+#define AK8963_ASAX      0x10  // Fuse ROM x-axis sensitivity adjustment value
+#define AK8963_ASAY      0x11  // Fuse ROM y-axis sensitivity adjustment value
+#define AK8963_ASAZ      0x12  // Fuse ROM z-axis sensitivity adjustment value
+
+
+
+//MPU9255 register
+#define ADO 0
+#if ADO
+#define MPU9255_ADDRESS 0x69<<1  // Device address when ADO = 1
+#else
+#define MPU9255_ADDRESS 0x68<<1  // Device address when ADO = 0
+#endif
+
+#define SELF_TEST_X_GYRO 0x00                  
+#define SELF_TEST_Y_GYRO 0x01                                                                          
+#define SELF_TEST_Z_GYRO 0x02
+
+#define SELF_TEST_X_ACCEL 0x0D
+#define SELF_TEST_Y_ACCEL 0x0E    
+#define SELF_TEST_Z_ACCEL 0x0F
+
+#define SELF_TEST_A      0x10
+
+#define XG_OFFSET_H      0x13  // User-defined trim values for gyroscope
+#define XG_OFFSET_L      0x14
+#define YG_OFFSET_H      0x15
+#define YG_OFFSET_L      0x16
+#define ZG_OFFSET_H      0x17
+#define ZG_OFFSET_L      0x18
+#define SMPLRT_DIV       0x19
+#define CONFIG           0x1A
+#define GYRO_CONFIG      0x1B
+#define ACCEL_CONFIG     0x1C
+#define ACCEL_CONFIG2    0x1D
+#define LP_ACCEL_ODR     0x1E   
+#define WOM_THR          0x1F   
+
+#define MOT_DUR          0x20  // Duration counter threshold for motion interrupt generation, 1 kHz rate, LSB = 1 ms
+#define ZMOT_THR         0x21  // Zero-motion detection threshold bits [7:0]
+#define ZRMOT_DUR        0x22  // Duration counter threshold for zero motion interrupt generation, 16 Hz rate, LSB = 64 ms
+
+#define FIFO_EN          0x23
+#define I2C_MST_CTRL     0x24   
+#define I2C_SLV0_ADDR    0x25
+#define I2C_SLV0_REG     0x26
+#define I2C_SLV0_CTRL    0x27
+#define I2C_SLV1_ADDR    0x28
+#define I2C_SLV1_REG     0x29
+#define I2C_SLV1_CTRL    0x2A
+#define I2C_SLV2_ADDR    0x2B
+#define I2C_SLV2_REG     0x2C
+#define I2C_SLV2_CTRL    0x2D
+#define I2C_SLV3_ADDR    0x2E
+#define I2C_SLV3_REG     0x2F
+#define I2C_SLV3_CTRL    0x30
+#define I2C_SLV4_ADDR    0x31
+#define I2C_SLV4_REG     0x32
+#define I2C_SLV4_DO      0x33
+#define I2C_SLV4_CTRL    0x34
+#define I2C_SLV4_DI      0x35
+#define I2C_MST_STATUS   0x36
+#define INT_PIN_CFG      0x37
+#define INT_ENABLE       0x38
+#define DMP_INT_STATUS   0x39  // Check DMP interrupt
+#define INT_STATUS       0x3A
+#define ACCEL_XOUT_H     0x3B
+#define ACCEL_XOUT_L     0x3C
+#define ACCEL_YOUT_H     0x3D
+#define ACCEL_YOUT_L     0x3E
+#define ACCEL_ZOUT_H     0x3F
+#define ACCEL_ZOUT_L     0x40
+#define TEMP_OUT_H       0x41
+#define TEMP_OUT_L       0x42
+#define GYRO_XOUT_H      0x43
+#define GYRO_XOUT_L      0x44
+#define GYRO_YOUT_H      0x45
+#define GYRO_YOUT_L      0x46
+#define GYRO_ZOUT_H      0x47
+#define GYRO_ZOUT_L      0x48
+#define EXT_SENS_DATA_00 0x49
+#define EXT_SENS_DATA_01 0x4A
+#define EXT_SENS_DATA_02 0x4B
+#define EXT_SENS_DATA_03 0x4C
+#define EXT_SENS_DATA_04 0x4D
+#define EXT_SENS_DATA_05 0x4E
+#define EXT_SENS_DATA_06 0x4F
+#define EXT_SENS_DATA_07 0x50
+#define EXT_SENS_DATA_08 0x51
+#define EXT_SENS_DATA_09 0x52
+#define EXT_SENS_DATA_10 0x53
+#define EXT_SENS_DATA_11 0x54
+#define EXT_SENS_DATA_12 0x55
+#define EXT_SENS_DATA_13 0x56
+#define EXT_SENS_DATA_14 0x57
+#define EXT_SENS_DATA_15 0x58
+#define EXT_SENS_DATA_16 0x59
+#define EXT_SENS_DATA_17 0x5A
+#define EXT_SENS_DATA_18 0x5B
+#define EXT_SENS_DATA_19 0x5C
+#define EXT_SENS_DATA_20 0x5D
+#define EXT_SENS_DATA_21 0x5E
+#define EXT_SENS_DATA_22 0x5F
+#define EXT_SENS_DATA_23 0x60
+#define MOT_DETECT_STATUS 0x61
+#define I2C_SLV0_DO      0x63
+#define I2C_SLV1_DO      0x64
+#define I2C_SLV2_DO      0x65
+#define I2C_SLV3_DO      0x66
+#define I2C_MST_DELAY_CTRL 0x67
+#define SIGNAL_PATH_RESET  0x68
+#define MOT_DETECT_CTRL  0x69
+#define USER_CTRL        0x6A  // Bit 7 enable DMP, bit 3 reset DMP
+#define PWR_MGMT_1       0x6B // Device defaults to the SLEEP mode
+#define PWR_MGMT_2       0x6C
+#define DMP_BANK         0x6D  // Activates a specific bank in the DMP
+#define DMP_RW_PNT       0x6E  // Set read/write pointer to a specific start address in specified DMP bank
+#define DMP_REG          0x6F  // Register in DMP from which to read or to which to write
+#define DMP_REG_1        0x70
+#define DMP_REG_2        0x71 
+#define FIFO_COUNTH      0x72
+#define FIFO_COUNTL      0x73
+#define FIFO_R_W         0x74
+#define WHO_AM_I_MPU9255 0x75 // Should return 0x73
+#define XA_OFFSET_H      0x77
+#define XA_OFFSET_L      0x78
+#define YA_OFFSET_H      0x7A
+#define YA_OFFSET_L      0x7B
+#define ZA_OFFSET_H      0x7D
+#define ZA_OFFSET_L      0x7E
+
+#endif
\ No newline at end of file