Giter Site home page Giter Site logo

mpu6050's Introduction

MPU-6050

Basic MPU-6050 Arduino sketch of sensor function

For a discussion of performance on various microcontroller platforms, uses and limitations of the MPU-6050 see here.

I have written a report from the June 11-12, 2014 Invensense Developers Conference.

This sketch demonstrates MPU-6050 basic functionality including initialization, accelerometer and gyro calibration, sleep mode functionality as well as parameterizing the register addresses. Added display functions to allow display to on-breadboard monitor. No DMP use. We just want to get out the accelerations, temperature, and gyro readings.

Runs on 3.3V 8 MHz Pro Mini and Teensy 3.1.

Added quaternion filter based on Madgwick's open-source sensor fusion algorithms. The MPU-6050 lacks a magnetic vector for absolute orientation estimation as is possible with the MPU-9150 or LSM9DS0. This algorithm allows estimation of quaternions and relative orientation, allowing output of Yaw, Pitch, and Roll which is subject to Yaw drift due to gyro bias drift. Despite the inclusion of a gyro bias drift correction component to the sensor fusion algorithm, Yaw drift is about half a degree per minute or less, which is not too bad. In principle, Yaw should not be possible to estimate with only a single absolute reference (gravity down), yet this algorithm does a good job of estimating relative Yaw with good stability over short time scales.

I have added code compiled with the mbed compiler to run 6-axis sensor fusion using the STM32MF401 ARM processor and the MPU-6050. Why would this be necessary or desirable?

The filter runs at a 200 Hz update rate on a 3.3 V 8 MHz Pro Mini AVR (Arduino) microcontroller.

The filter runs at a 3200 Hz update rate on a 3.3 V 96 MHz Teensy 3.1 ARM microcontroller.

The filter runs at a 5500 Hz update rate on a 3.3 V 84 MHz STM32F401 ARM microcontroller.

One doesn't need more that about 1000 Hz sensor fusion filter update rate to get optimal performance from 6- and 9-axis motion sensors, but the power consumption is proportional to the microcontroller clock speed. If that 1000 Hz rate can be achieved at a lower clock speed, then lower power consumption can be achieved. This is a critical consideration for portable (wearable) motion sensing and motion control devices.

Let's assume the sensor fusion filter update rate is linearly proportional to the clock speed (a pretty good assumption). Then to get 1000 Hz update rates for the Teensy only requires 96/3.2 = 30 MHz clock speed. In fact, at 24 MHz clock speed the update rate with the Teensy 3.1 is 1365 Hz. For the STM32F401, the clock speed needs to be only 84/5.5 = 16 MHz to reach a sensor fusion filter update rate of 1000 Hz. In practice, the clock speeds are not arbitrary but must meet certain constraints; it might not be possible to run the STM32F401 at such a low speed. So far, I have only run it at 84 and 42 MHz; at 42 MHz I got sensor fusion filter update rates of ~4400 Hz. It appears that the STM32F401 would require less than half the power compared to the Teensy 3.1 to achieve the same level of sensor fusion performance. Meaning that all else being equal (it never is!), a wearable device using the STM32F401 as the microcontroller could last twice as long before battery change or charging is required. This is a major commercial advantage and why the STM32 M4 Cortex family of processors is so interesting.

mpu6050's People

Contributors

bsvdoom avatar kriswiner avatar mohameda95 avatar redglasses avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

mpu6050's Issues

About the Hard and Soft-Iron Calibration

Hello, I have read the hard-iron and soft-iron magnetic field calibration in your Wiki 'Simple and Effective Magnetometer Calibration':

// Get hard iron correction
mag_bias[0] = (mag_max[0] + mag_min[0])/2; // get average x mag bias in counts
mag_bias[1] = (mag_max[1] + mag_min[1])/2; // get average y mag bias in counts
mag_bias[2] = (mag_max[2] + mag_min[2])/2; // get average z mag bias in counts

dest1[0] = (float) mag_bias[0]_MPU9250mRes_MPU9250magCalibration[0]; // save mag biases in G for main program
dest1[1] = (float) mag_bias[1]_MPU9250mRes_MPU9250magCalibration[1];
dest1[2] = (float) mag_bias[2]_MPU9250mRes_MPU9250magCalibration[2];

// Get soft iron correction estimate
mag_scale[0] = (mag_max[0] - mag_min[0])/2; // get average x axis max chord length in counts
mag_scale[1] = (mag_max[1] - mag_min[1])/2; // get average y axis max chord length in counts
mag_scale[2] = (mag_max[2] - mag_min[2])/2; // get average z axis max chord length in counts

float avg_rad = mag_scale[0] + mag_scale[1] + mag_scale[2];
avg_rad /= 3.0;

dest2[0] = avg_rad/((float)mag_scale[0]);
dest2[1] = avg_rad/((float)mag_scale[1]);
dest2[2] = avg_rad/((float)mag_scale[2]);

I would like to ask that what are the array dest1 and dest2?
Does this mean that I have to substrate the original mag data with the dest1 for hard-iron calibration? How about dest2?
Thanks in advance!

fifo_count is always 8 after 80 msec @1K hz

I want to read FIFO continuously. So I copied calibrateMPU6050 in a new function and in the loop I wait for 80 msec and then read fifo_count but I always one data packet.
void setup(){
......
uint8_t c = mpu.readByte(MPU6050_ADDRESS, WHO_AM_I_MPU6050);
Serial.print("I AM ");
Serial.print(c, HEX);
Serial.print(" I Should Be ");
Serial.println(0x68, HEX);
// my mpu6050 return 0x98
if((c == 0x68) || (c==0x98)){
{
Serial.println("MPU6050 is online...");
}

mpu.InitialteFIFO();
LastRead=millis();
}
}
while((millis()-LastRead)<80)// I already enabled FIFO in the InitializeByFIFO()
{
delayMicroseconds(50);
}
LastRead=millis();
fifo_count=0;
while(fifo_count<512)// I already enabled FIFO in the InitializeByFIFO()
{
// At end of sample accumulation, turn off FIFO sensor read
mpu.writeByte(MPU6050_ADDRESS, FIFO_EN, 0x00); // Disable gyro and accelerometer sensors for FIFO
mpu.readBytes(MPU6050_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
Serial.println("");
Serial.print(" FC:");
Serial.println( fifo_count);
for (ii = 0; ii < packet_count; ii++) {
int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0};
mpu.readBytes(MPU6050_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]) ;
Serial.print(" X:");
Serial.print(accel_temp[0]); // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases
Serial.print(" Y:");
Serial.print(accel_temp[1]);
Serial.print(" Z:");
Serial.print(accel_temp[2]);
Serial.print(" GX:");
Serial.print(gyro_temp[0]);
Serial.print(" GY:");
Serial.print(gyro_temp[1]);
Serial.print(" GZ:");
Serial.println(gyro_temp[2]);

}

}
In the MPU6050.cpp
void MPU6050lib::InitialteFIFO()
{
// reset device, reset all registers, clear gyro and accelerometer bias registers
writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
delay(100);

// get stable time source
// Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001
writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x01);
writeByte(MPU6050_ADDRESS, PWR_MGMT_2, 0x00);
delay(200);

// Configure device for bias calculation
writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts
writeByte(MPU6050_ADDRESS, FIFO_EN, 0x00); // Disable FIFO
writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x00); // Turn on internal clock source
writeByte(MPU6050_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master
writeByte(MPU6050_ADDRESS, USER_CTRL, 0x00); // Disable FIFO and I2C master modes
writeByte(MPU6050_ADDRESS, USER_CTRL, 0x0C); // Reset FIFO and DMP
delay(15);

// Configure MPU6050 gyro and accelerometer for bias calculation
writeByte(MPU6050_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz
writeByte(MPU6050_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz
writeByte(MPU6050_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to 250 degrees per second, maximum sensitivity
writeByte(MPU6050_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 Interrupts and Bypass Enable
// Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips
// can join the I2C bus and all can be controlled by the Arduino as master
writeByte(MPU6050_ADDRESS, INT_PIN_CFG, 0x22);
writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x01); // Enable data ready (bit 0) interrupt
delay(15);
// Configure FIFO to capture accelerometer and gyro data for bias calculation
writeByte(MPU6050_ADDRESS, USER_CTRL, 0x40); // Enable FIFO
writeByte(MPU6050_ADDRESS, FIFO_EN, 0x78); // Enable gyro and accelerometer sensors for FIFO (max size 1024 bytes in MPU-6050)
}

Strange reset behaviour

It works as intended after the first sketch upload. After that if I unplug usb cable thus cutting the both devices power and plug back - the fun starts here) The sketch is working, but this time the response from mpu9250 is like 10 times slower. Here is the weird part - it still works, but just shows the data slower in Serial Monitor and the led blinks slower.

What am I doing wrong? I'm using Arduino Pro Micro (324u4 chip) and 9250 board. Thanks.

MPU6050IMU.ino accelerometer offset - temperature compensation bit

Hi Kris,

I stumbled over you code when researching MPU6050 accelerometer bias correction.
Thank you very much for sharing

Maybe I spotted kind of a bug - please verify:
When you calculate
accel_bias_reg[2] -= (accel_bias[2]/8);
then you might accidently set the lowest (i.e. temperature compensation) bit even if it has not been set previously.

Best Regards,

Helmut

About automatic calibrations of magnetometer

Hello, I have read your article "Simple and Effective Magnetometer Calibration". Do you have any further information about how to do the automatic calibration and let the users know if the magnetometer is well-calibrated and how well they can trust the result after calibration? I can only show the plot figure of mag data to myself; however, I can not know if the magnetometer is well-calibrated and can be used. Thanks in advance!

LSM9DS1 vs. MPU-9250 vs. BMX055

Hi.

I was wondering if you had made any comparison on these 3 chips, especially in terms of the magnetometer, which has been a big problem for me on the Invensense in terms of error.

Initial accelerometer calibration

Hello Kris!

First of all thank you for your great work and for sharing knowledge so other can learn!

I am new with the MPU-6050 and I am trying to understand the auto calibration process that you have implemented. If I understand correctly, all is based on ideal situations, e.g. the sensor is located with one axis (z axis) along the gravity vector and other axis having 0g, the sensor have ideal performance characteristics and is temperature is stable, among others.

Then if we believe that we positioned the sensor in the ideal position, we then adjust the measurements by adding offsets to match the ideal case. Is this what you are doing? is this the same as this https://github.com/jrowberg/i2cdevlib/blob/master/Arduino/MPU6050/examples/IMU_Zero/IMU_Zero.ino

Can this be called calibration? I am really confuse if it is necessary to calibrate MEMS accelerometers or if they are adjusted from factory. Could you please elaborate more on this topic of calibration and what the sensor is given from factory?

Thank you once again!

magnetic calibration

Hi Kris, for 8-shape magnetic calibration. Do i need to move in 8-shape for all three dimensions (x, y, z)?
This what happens when I did on all directions on my chip. I am using uT units. And does it has to be around 0 like what you have done. Thank you very much.

image

[Question] how to compute relative position (vector) with sensor fusion?

@kriswiner Hi,

Thanks for your work on sensor fusion. It has been a real help for my classmates and I. It's also great that you got interested in porting your work on the STM32 board family, these are great products.

For our school project, we're more interested in the trajectory than in the orientation of the sensor (in other words "where is it going in 3D space").

How can we retrieve that information based on sensor fusion ? We have the same breakout bord as described in your article.

We're not algebra masters so we don't really know how to compute this data.

Any ideas ?

Thanks in advance,

Help with magnetometer calibration

I'm a student and i want to use the MPU 9250 module for a proyect, but im having problems with the yaw values, it seems like it is a magnetometer calibration problem and i was trying to use the function you posted, but I don't really know how to implement it using Arduino Uno. I hope you can help me with this proyect, please. Thank you in advance for your time.

MPU6050 Calibrated Acc and Gyro in different measurement range

If you see source code for IMU you will see using DMP or raw data but none has given more realistic solution for applied project. I'm using raw data and I get offset when MPU6050 is set to measure +/-2g and 250 DPS. I store them in an int16 array so aRes is Acc rang and gyro rang /32768.0. Now, when I read sensor in a loop, I have to get calibrated value:
(float) (Ax-(offsetAX/ADIVIDER))*aRes;
(float) (Gx-(offsetGX/GDIVIDER))*gRes;
ADIVIDER for 2g is 1 and for 16g is 8
GDIVIDE for 250 DPS is 1 and for 2000 DPS is 8
Even though, the method is much better than others but in gyro I see offset about 1-7 as I expected to have 0.

Reason behind not using the interrupt functionality?

Your sketches have proven very useful and you clearly know what you are doing. I ordered an 'Ultimate IMU' from tindie.
What is the reason you do not use the interrupt pin? I2Cdevlib uses it, and your sketch mentions it as well.

icm 20948 wake on motion interrupt

Hi,
I am facing a problem in icm 20948 with msp430fr5994 by using int .i set a threshold values so that onece when my threshold values is cross i should get int but here it is not happening like that without crossing also i am getting int .I was suspecting that setting of threshold value in register is not proper .
the following is my code

//macros used
//interrupts
const uint8_t REG_ACCEL_INTEL_CTRL =0x12;//userbank2
const uint8_t BIT_ACCEL_INTEL_EN =0x02;//Wake-up On Motion enable bit
const uint8_t BIT_ACCEL_INTEL_MODE =0x01;//WOM algorithm selection bit
const uint8_t REG_ACCEL_WOM_THR = 0x13; //_BANK_2 // Wake-up On Motion Threshold register
const uint8_t BIT_SLEEP =0x40; //bank0 reg 0x06 /< Sleep mode enable bit
const uint8_t BIT_SLEEP_CLEAR=0x00;//clear bit sleepin ub0,reg6
const uint8_t REG_PWR_MGMT_1 =0x06;//bank0 /
< Power Management 1 register
const uint8_t REG_LP_CONFIG = 0x05;// bnk0,reg,5 //Low Power mode config register
const uint8_t BIT_ACCEL_CYCLE= 0x20;////bank0,reg,5writhe this value /< Accelerometer cycle mode enable
const uint8_t BIT_GYRO_CYCLE = 0x10;//bank0,reg5,write this value /
< Gyroscope cycle mode enable
const uint8_t REG_GYRO_SMPLRT_DIV =0x00;//bank2,reg0 /< Gyroscope Sample Rate Divider regiser
const uint8_t REG_ACCEL_SMPLRT_DIV_1 = 0x10;//bank2,reg 10 /
< Acceleration Sensor Sample Rate Divider
const uint8_t REG_ACCEL_SMPLRT_DIV_2 = 0x11;//bank2,reg11 /< Acceleration Sensor Sample Rate Divider 2 register */
const uint8_t SHIFT_ACCEL_DLPCFG = 3; /
< Accel DLPF Config bit shift */
const uint8_t BIT_PWR_ACCEL_STBY= 0x07; //bank0,reg7 /< Disable accelerometer */
const uint8_t BIT_WOM_INT_EN = 0x08;//bank0,reg10 /
< Wake-up On Motion enable bit */
const uint8_t B0_REG10=0x10;
const uint8_t EN_GYRO=0x38;
const uint8_t REG_INT_STATUS= 0x19;//bnk0 /< Interrupt Status register */
const uint8_t BIT_WOM_INT = 0x08; /
< Wake-up on motion interrupt occured bit */
const uint8_t BIT_PLL_RDY = 0x04; /**< PLL ready interrupt occured bit */

int Enable_WOM_Interrupt()
{
if (changeUserBank(USER_BANK_0,0) < 0)//selecting userbank0
{
return -1;
}
if (I2C_WRITE(UB0_INT_PIN_CFG, UB0_INT_PIN_CFG_HIGH_50US) < 0)
{
return -2;
}
enable_sleepmode(false);//chacking if//it is sleep mode or not
enable_cyclemode(false);//operating in duty cycle mode
enable_sensor(true,false);//enablling accelemeter
set_sample_rate(1100.0);
enable_irq(true);//ensbling wom int
if (configAccel(ACCEL_RANGE_16G, ACCEL_DLPF_BANDWIDTH_1209HZ) < 0)//scale range 16g
{
return -3;
}
enable_irq();
__delay_cycles(50);

if (changeUserBank(USER_BANK_2,0) < 0)
{
return -4;
}
if (I2C_WRITE(REG_ACCEL_INTEL_CTRL, BIT_ACCEL_INTEL_EN|BIT_ACCEL_INTEL_MODE) < 0)//enablewomlogic,comparingprevious with current sample
{
return -5;
}

if (changeUserBank( USER_BANK_0,0) < 0)

{
return -6;
}
readSensor();
if (changeUserBank(USER_BANK_2,0) < 0)
{
return -6;
}
if (I2C_WRITE(REG_ACCEL_WOM_THR,x_Threshold)<0)//setting_threshold_value
{
return -7;
}
enableInterrupt(GPIO_PORT_P4, GPIO_PIN4);
}
uint32_t enable_irq( )
{
if (changeUserBank( USER_BANK_0,0) < 0)
{
return -1;
}
else if( I2C_WRITE(B0_REG10,BIT_WOM_INT_EN)<0)
{
return -2;
}
return 1;
}
int enable_sleepmode(bool enable)
{

    if (enable)
    {
        if (changeUserBank( USER_BANK_0,0) < 0)
        {
            return -1;
        }

         if( I2C_WRITE(REG_PWR_MGMT_1,BIT_SLEEP)<0)
           {
            return -2;

           }
    }
    else
    {
        if (changeUserBank( USER_BANK_0,0) < 0)
        {
            return -1;
        }
         if( I2C_WRITE(REG_PWR_MGMT_1,BIT_SLEEP_CLEAR)<0)
          {
            return -2;
           }
    }

    return 1;

}

int enable_cyclemode(bool enable)
{

if (enable)
{
    if (changeUserBank( USER_BANK_0,0) < 0)
    {
        return -1;
    }
    if(I2C_WRITE(REG_LP_CONFIG,(BIT_ACCEL_CYCLE|BIT_GYRO_CYCLE))<0)
    {
        return -2;
    }
}
else
{

    if (changeUserBank( USER_BANK_0,0) < 0)
    {
        return -1;
    }
    if(I2C_WRITE(REG_LP_CONFIG,(BIT_ACCEL_CYCLE&BIT_GYRO_CYCLE))<0)
           {
               return -2;
           }
}
return 1;

}
uint32_t set_sample_rate(float sampleRate)
{
set_gyro_sample_rate(sampleRate);
set_accel_sample_rate(sampleRate);

return 1;

}
float set_gyro_sample_rate(float sampleRate)
{
uint8_t gyroDiv;
float gyroSampleRate;

/* Calculate the sample rate divider */
gyroSampleRate = (1125.0 / sampleRate) - 1.0;

/* Check if it fits in the divider register */
if ( gyroSampleRate > 255.0 )
{
    gyroSampleRate = 255.0;
}

if ( gyroSampleRate < 0 )
{
    gyroSampleRate = 0.0;
}

/* Write the value to the register */
gyroDiv = (uint8_t) gyroSampleRate;
if(changeUserBank( USER_BANK_2,0) < 0)
{
    return -1;
}
if(I2C_WRITE(REG_GYRO_SMPLRT_DIV, gyroDiv)<0)
{
    return -2;
}

/* Calculate the actual sample rate from the divider value */
gyroSampleRate = 1125.0 / (gyroDiv + 1);

return gyroSampleRate;

}
float set_accel_sample_rate(float sampleRate)
{
uint16_t accelDiv;
float accelSampleRate;

/* Calculate the sample rate divider */
accelSampleRate = (1125.0 / sampleRate) - 1.0;

/* Check if it fits in the divider registers */
if ( accelSampleRate > 4095.0 ) {
    accelSampleRate = 4095.0;
}

if ( accelSampleRate < 0 ) {
    accelSampleRate = 0.0;
}

/* Write the value to the registers */
accelDiv = (uint16_t) accelSampleRate;
I2C_WRITE(REG_ACCEL_SMPLRT_DIV_1, (uint8_t) (accelDiv >> 8) );
I2C_WRITE(REG_ACCEL_SMPLRT_DIV_2, (uint8_t) (accelDiv & 0xFF) );

/* Calculate the actual sample rate from the divider value */
accelSampleRate = 1125.0 / (accelDiv + 1);

return accelSampleRate;

}
uint32_t enable_sensor(bool accel, bool gyro)
{
// uint8_t pwrManagement1;
// uint8_t pwrManagement2;

// pwrManagement2 = 0;
if ( accel )
{
if (changeUserBank(USER_BANK_0,0) < 0 )
{
I2C_WRITE(UB0_PWR_MGMNT_2, BIT_PWR_ACCEL_STBY);

     return -1;
 }
}
else if ( gyro )
{
    if (changeUserBank(USER_BANK_0,0) < 0 )
    {
      I2C_WRITE(UB0_PWR_MGMNT_2, EN_GYRO);
        return -2;
    }

}

return 1;

}

this is when i get interuupt in took a pin
void int_pin()
{
GPIO_setAsInputPin(GPIO_PORT_P4,GPIO_PIN4);
GPIO_setAsInputPinWithPullUpResistor(GPIO_PORT_P4,GPIO_PIN4);
GPIO_selectInterruptEdge(GPIO_PORT_P4, GPIO_PIN4, GPIO_LOW_TO_HIGH_TRANSITION);
GPIO_clearInterrupt(GPIO_PORT_P4,GPIO_PIN4);

}

#pragma vector=PORT4_VECTOR
__interrupt void Port_4(void) //ISR

{
Tx_Uart0_String("\nharsh_braking");///when my threshold values crosses it should here but if axis
value is less than threshold value then also it is in isr and not clearing

GPIO_clearInterrupt(GPIO_PORT_P4, GPIO_PIN4);

}
so is there any thing i need to add or change should be done mail me [email protected] as early as possible
so i haave codded in such a format that i keep on reading accelerometer axis values but once threshold values crosses reaches ISR
Thanks in advance

InvenSense ICM-20948 DMP Flash error

Hi,
I am using ICM-20948 by TDK InvenSense, which has on board digital motion processing unit. My host processor is MediaTek MT-2523G.
InvenSense provides DMP firmware, that has to be programed on DMP to access it features. I am using I2C to communicate with ICM-20948. I am able to get the RAW accel data. But when I try to write the firmware bytes on DMP, somehow my writes are not getting to its memory.
I've seen on InvenSense developers form, most of the people are facing this issue. When I write the bytes to DMP memory, I get ACK from the device, but when I try to verify the DMP memory, I recieve garbage values.
I would be very thankful, if I get solution of this problem.

Furthermore, is there any activity recognition library, which take axis data as input and tells us user's activity.

Magnetometer raw data issue

Hello, in first place I want to thank you for the amazing work about MPU9250. Even though I’m a student I have very little practical knowledge about sensor fusion (new to the topic), so having a guide like yours means a lot, a ton!

And now about the problem, ill tri to be as simple as possible. So I hooked up my MPU9250, setu up the communication and so on… I can easly access the raw data registers from AK8963. The problem is the measurement. In your article “Simple and Effective Magnetometer Calibration” ,the first picture shows raw data from AKA8963, The blue marks indicates the change in magnetic field along the xy plane.

I rotated the module for 360 degrees in the xy plane and my measurements of the magnetic field along the plane, with the z pointing to ground shows this:

proba

(The transition from nord to east is shown by the red rhomb)

Could you give me an opinion about what the problem might be, and how to fix it?

1kHz IMU for Google Cardboard ?

Do you happen to know of any plug and play IMU kit that would work with (almost) any Android phone for Google Cardboard head tracking? (to match whatever sensors Gear VR has)

Calibration values question

Hi,
Thanks for this but I hope you have time for a couple of questions about the code...
I am trying to convert this for use on a QMC5883L chip (sometimes you just have to work with what arrives).
This says its 16bit but does not actually say anywhere what unit-of-measure the registers return, just that they are 16 bit integer from -32768 to 32767.
It also does not have any factory calibration nor scale - or none that are published anyway.

so for the lines of code like ...
dest1[0] = (float) mag_bias[0] * mRes * MPU9250magCalibration[0];
mx = (float)magCount[0]mResmagCalibration[0] - magBias[0];
I have eliminated MPU9250magCalibration

In the main program I have also found you have defined mres for 16bit values as.......
mRes = 10.*4912./32760.0

Can you please explain the magic of these values ?

My original sketch had simply
float heading = (atan2((float)y,(float)x));
headingDegrees = (heading * C_rad_to_deg);
this mostly worked except for non-linear values < 50degrees - whereupon people tell me I have to calibrate the animal first !

I think I understand adjusting by the bias ie "- magBias[0]"
and scaling ie mx *= magScale[0];
but the presence of mRes is escaping me.

Thanks in anticipation
JC

Pb with self-test

Hello Kris

First of all, thank you for your work and for sharing it.

I am a beginner with MPU6050 and I am reading your code in order to understand the lacks in the documentation of Invense. I have two questions

  1. In your SelfTest() function code, there are lines such as :
    selfTest[0] = (rawData[0] >> 3) | (rawData[3] & 0x30) >> 4
    I wonder if (rawData[0] >> 3) would not be replaced with (rawData[0] >> 3) & ~0b11
    in order to kill bit-0 and bit-1 ?
    Without & ~0b11, it could generate a little error up to 3, no ?
  2. I have also a question about bit-0 in accel bias register.
    Can we arbitrarily set them to 0 or 1, and what is the influence of each choice
    on the temperature compensation?

Thank you in advance for your reply

J.M. CORNIL

Implement calibrations of Magnetometer

Thank you for your codes and tutorials, very helpful,
for the Magnetometer calibration:
after calibration the bias we just subtract it from our magnetometer readings?
what about the scale, multiply it by the readings?

FIFO_R_W

Dear Friends,
i have working with MPU6050 and (I2C) 8byte register Microcontroller,
i have problem in adding this line
readBytes(MPU6050_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging

because this line shows to get 12 byte from the registers
but my microcontroller have only 8byte register,

so can i write the above line like
readBytes(MPU6050_ADDRESS, FIFO_R_W, 6, &data[0]);
accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1] ) ;
accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3] ) ;
accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5] ) ;
readBytes(MPU6050_ADDRESS, FIFO_R_W, 6, &data[0]);
gyro_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1] ) ;
gyro_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3] ) ;
gyro_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5] ) ;

i hope i get answer soon as possible thank you,

with regards
kannannatesh.S

pitch and roll variation

Dear Kris,
many thanks for the great code you provided,
I used arduino nano to collect data from the mpu-6050 sensor using the code
MPU6050IMU.ino
by: Kris Winer
date: May 10, 2014
I removed the display and added a serial print to get the result.
I collected the data for more than 10 minutes and got the following summarized result

ROLL : minimum -0.31 ; maximum 1.00 ; ravage 0.322729 ; variation +- 0.65
Pitch : minimum -0.02 ; maximum 1.30 ; ravage 0.64 ; variation +- 0.65

as you can see the variation is high- around one degree - while in the DMP its around 0.1 degree for roll and pitch.

do you get the same result or have I done a mistake?
your clarification is highly appreciated.

Best Regards,
Hassan

roll

offset increasing

Hello mr kris,Thank you for your great effort and dedication. Your code has really helped me a lot.
I tested your code using MPU6050 sensor and an arduino uno board it works fine while i keep rotating the sensor but when I stop moving the sensor the values of yaw, pitch and roll angles increase by time. So the offset increases and affects the future outputs.
Please, do you have any idea what am i doing wrong?
Thanks in advance

Madgwick Quaternions without accelerometer data

Hello Kris,

First of all, thanks for this old but very useful library.

Is it possible to use the MadgwickQuaternionUpdate without Accel inputs?

I am in the process of creating a model rocket flight computer and I suspect the fusion of the Gyro with accelerometer cannot be used in this application because of the high acceleration inherent to rockets.

I do however need the integration of the angular velocity of the gyro axis into Quaternions.

I tried to strategically place a if statement in the code of the MadgwickQuaternionUpdate to ignore the Accel data if 0,0,0 is passed for the 3 accel axis. However, I am unfortunately not gifted for complex algebra and so far I haven't had much success.

Is this something you can help with?

Best regards.

Self test

The self test implementation doesn't make sense to me, and doesn't appear to match the guidance in the register map (rev 4.2 at least). Is there some additional documentation from Invensense supporting your implementation? The expression at line 692 effectively calculates the percent difference between the (encoded) values stored in registers 0x0d-0x10, and the (decoded) values produced using the conversion expressions in lines 676-681. For a given chip this result will be fixed and will be pretty close to -100%. How does this test the sensor? Isn't the factory trim result supposed to be compared instead with Self Test Response, which the register map defines as the difference between a (real-time) sensor reading with self-test enabled and a (real-time) sensor reading with self-test disabled? If this understanding is wrong I'd be interested in knowing that.

MPU9250 ODR

hi,
i'm making some research to understand the sensor's panorama, and i would like to understand what is the ODR of MPU9250, i undertand that accelerometer can go up to 4kHz, from your codde that magne is read at 100Hz, but what about gyro? also how did you find taht value? the datasheet is so inconsistent! maybe you directly look up to single chip DS?

Uff invsense make all think so complicated, ST datasheet are much better :/

Also i have some modification to original DCM implementation, basically just some code refractor, see https://github.com/MauroMombelli/FreeDCM

Sensor Temperature Compensation

Hello there! First off, huge thanks for this library, it has saved me lots of trouble already.
However, there is one thing I do not quite know how to do, and this is gyroscope/accelerometer temperature compensation. I have experienced significant drift when the sensor is not freshly calibrated, and would like to manually change the offsets with varying temperature. Is there an equation or something I am missing? Or is the only way to gather data in different temperature conditions?

Not sure how to compile successfully for Teensy 4.0.

I download the github repo and extract it to my Arduino folder in My Documents. Then, I try and run MUP6050IMU.ino file and it says "MadgwickQuaternionUpdate' was not declared in this scope".

If I try and run MPU6050BasicExample.ino it errors out with this:

Linking everything together...
"C:\\Program Files (x86)\\Arduino\\hardware\\teensy/../tools/arm/bin/arm-none-eabi-gcc" -O2 -Wl,--gc-sections,--relax "-TC:\\Program Files (x86)\\Arduino\\hardware\\teensy\\avr\\cores\\teensy4/imxrt1062.ld" -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-d16 -o "C:\\Users\\Adam\\AppData\\Local\\Temp\\arduino_build_437672/MPU6050BasicExample.ino.elf" "C:\\Users\\Adam\\AppData\\Local\\Temp\\arduino_build_437672\\sketch\\MPU6050.cpp.o" "C:\\Users\\Adam\\AppData\\Local\\Temp\\arduino_build_437672\\sketch\\MPU6050BasicExample.ino.cpp.o" "C:\\Users\\Adam\\AppData\\Local\\Temp\\arduino_build_437672\\libraries\\Wire\\Wire.cpp.o" "C:\\Users\\Adam\\AppData\\Local\\Temp\\arduino_build_437672\\libraries\\Wire\\WireIMXRT.cpp.o" "C:\\Users\\Adam\\AppData\\Local\\Temp\\arduino_build_437672\\libraries\\Wire\\WireKinetis.cpp.o" "C:\\Users\\Adam\\AppData\\Local\\Temp\\arduino_build_437672\\libraries\\Wire\\utility\\twi.c.o" "C:\\Users\\Adam\\AppData\\Local\\Temp\\arduino_build_437672/core\\core.a" "-LC:\\Users\\Adam\\AppData\\Local\\Temp\\arduino_build_437672" -larm_cortexM7lfsp_math -lm -lstdc++
C:\Users\Adam\AppData\Local\Temp\arduino_build_437672\sketch\MPU6050BasicExample.ino.cpp.o:(.bss.Ascale+0x0): multiple definition of `Ascale'
C:\Users\Adam\AppData\Local\Temp\arduino_build_437672\sketch\MPU6050.cpp.o:(.bss.Ascale+0x0): first defined here
c:/program files (x86)/arduino/hardware/tools/arm/bin/../lib/gcc/arm-none-eabi/5.4.1/../../../../arm-none-eabi/bin/ld.exe: Disabling relaxation: it will not work with multiple definitions
C:\Users\Adam\AppData\Local\Temp\arduino_build_437672\sketch\MPU6050BasicExample.ino.cpp.o: In function `getGres()':
C:\Users\Adam\Documents\Arduino\MPU6050-master\MPU6050BasicExample/MPU6050BasicExample.ino:237: multiple definition of `Gscale'
C:\Users\Adam\AppData\Local\Temp\arduino_build_437672\sketch\MPU6050.cpp.o:C:\Users\Adam\AppData\Local\Temp\arduino_build_437672\sketch/MPU6050.cpp:169: first defined here
collect2.exe: error: ld returned 1 exit status
Using library Wire at version 1.0 in folder: C:\Program Files (x86)\Arduino\hardware\teensy\avr\libraries\Wire 
Error compiling for board Teensy 4.0.

I've got .h and .ccp files in the same folder as the example file.

convert it a library

hi,
is it possible to convert the functions and the code to an arduino library so it becomes easier to use, by #including it to our file with out having to add the whole code to our file?
ps. i am willing to help if it is possible

Accel Bias

Hi,

I was looking at your file "MPU9250_MS5637_AHRS_t3" and there is something that I don't understand.
at the line 373 when you used this function :

accelgyrocalMPU9250(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers

Here you store in the internal registers of the MPU9250 biais from the Gyro and Accel. Then line 478 in the main loop you substract it again :

// Now we'll calculate the accleration value into actual g's ax = (float)MPU9250Data[0]*aRes - accelBias[0]; // get actual g value, this depends on scale being set ay = (float)MPU9250Data[1]*aRes - accelBias[1]; az = (float)MPU9250Data[2]*aRes - accelBias[2];

I thought that when you store the offset value in the MPU9250, it do it by itself to substract the offset. Maybe there is something that I miss understood ?

Thanks in advance for your help

Cheers

Pierre Gogendeau

Calibration Function

hello Kiris, thank you so much for your great work i am new to MPU and it is really helpful , i have a question i cannot understand the algorithm of the calibration function , could you send me any paper that talks about calibration you followed in your code ?

Thank you! You're awesome!

This is an AMAZING writeup. Thank you for making such a clear, helpful and useful guide of all the different 9-DOF IMU options and explanation of sensor fusion . Also your code is awesome :)

Magnetic Distortion Compensation

Are you incorporating 'magnetic distortion compensation' yet?

You are probably aware of Madgwick's comments on DIYdrones starting at
http://diydrones.com/xn/detail/705844:Comment:193246

"My paper does present what I believe to be a notable unique feature (as identified by Michael Zaffuto): the computation of a reference direction of magnetic flux. This (1) eliminates the need for the designer to predefine this, and (2) prevents magnetic distortions (soft-iron errors) from corrupting pitch or roll.

Conclusion:
Mahony’s algorithm is computationally less expensive and more ‘elegant’. In my own work, I now use Mahony’s for these reason but I combine it with my ‘magnetic distortion compensation’ algorithm for the reasons given above."

From a following comment, his modification of Mahony seems to increase the computation by about 20%, with the above advantages of his own algorithm.

Also - in terms of your excellent wiki page, you describe Madgwick's work before referencing his algorithm by name; it might be good to also say something about Mahony before referencing his algorithm in the table. Minor tweak. (The comment from Madgwick linked above does a good job of describing the differences, I think).

Merge the two projects: Aritro Mukherjee and yours

I'm not new to projects or programing, but at the basic level.

I am trying to understand how IMU's work.

For that I'm reading both projects (yours and https://github.com/AritroMukherjee/MPU5060sensor) and trying to merge them because I have a 10DOF waveshare version 2 IMU (https://www.waveshare.com/10-dof-imu-sensor-b.htm).

The idea is to create a line of variables that link the two projects in the processing program, only with the SDA and SCL pins connected to ARDUINO UNO.

At this moment, I can see the serial lines in the processing side but nothing happens in the display of the processing when I move the IMU. Is this the correct way?

There other issues but if I overcome this variables issue I think I'm starting to understand how IMU's work.

Thank you for your work.
Best.
António

seek help:how can i get the angle without using Arduino

Hello , sir . in your demonstration,we can get information from mpu6050 by using arduino,but if i want get information by mpu6050 and usb-i2c transverter instead of arduino ,what should a freshman do .Can you give me a train of thought,Thanks a million!

Problem with continues reading FIFO

I want to read FIFO continuously. So I copied calibrateMPU6050 in a new function and in the loop I wait for 80 msec and then read fifo_count but I always one data packet.
void setup(){
......
uint8_t c = mpu.readByte(MPU6050_ADDRESS, WHO_AM_I_MPU6050);
Serial.print("I AM ");
Serial.print(c, HEX);
Serial.print(" I Should Be ");
Serial.println(0x68, HEX);
// my mpu6050 return 0x98
if((c == 0x68) || (c==0x98)){
{
Serial.println("MPU6050 is online...");
}

mpu.InitialteFIFO();
LastRead=millis();
}
}
while((millis()-LastRead)<80)// I already enabled FIFO in the InitializeByFIFO()
{
delayMicroseconds(50);
}
LastRead=millis();
fifo_count=0;
while(fifo_count<512)// I already enabled FIFO in the InitializeByFIFO()
{
// At end of sample accumulation, turn off FIFO sensor read
mpu.writeByte(MPU6050_ADDRESS, FIFO_EN, 0x00); // Disable gyro and accelerometer sensors for FIFO
mpu.readBytes(MPU6050_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
Serial.println("");
Serial.print(" FC:");
Serial.println( fifo_count);
for (ii = 0; ii < packet_count; ii++) {
int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0};
mpu.readBytes(MPU6050_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]) ;
Serial.print(" X:");
Serial.print(accel_temp[0]); // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases
Serial.print(" Y:");
Serial.print(accel_temp[1]);
Serial.print(" Z:");
Serial.print(accel_temp[2]);
Serial.print(" GX:");
Serial.print(gyro_temp[0]);
Serial.print(" GY:");
Serial.print(gyro_temp[1]);
Serial.print(" GZ:");
Serial.println(gyro_temp[2]);

}

}
In the MPU6050.cpp
void MPU6050lib::InitialteFIFO()
{
// reset device, reset all registers, clear gyro and accelerometer bias registers
writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
delay(100);

// get stable time source
// Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001
writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x01);
writeByte(MPU6050_ADDRESS, PWR_MGMT_2, 0x00);
delay(200);

// Configure device for bias calculation
writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts
writeByte(MPU6050_ADDRESS, FIFO_EN, 0x00); // Disable FIFO
writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x00); // Turn on internal clock source
writeByte(MPU6050_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master
writeByte(MPU6050_ADDRESS, USER_CTRL, 0x00); // Disable FIFO and I2C master modes
writeByte(MPU6050_ADDRESS, USER_CTRL, 0x0C); // Reset FIFO and DMP
delay(15);

// Configure MPU6050 gyro and accelerometer for bias calculation
writeByte(MPU6050_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz
writeByte(MPU6050_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz
writeByte(MPU6050_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to 250 degrees per second, maximum sensitivity
writeByte(MPU6050_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 Interrupts and Bypass Enable
// Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips
// can join the I2C bus and all can be controlled by the Arduino as master
writeByte(MPU6050_ADDRESS, INT_PIN_CFG, 0x22);
writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x01); // Enable data ready (bit 0) interrupt
delay(15);
// Configure FIFO to capture accelerometer and gyro data for bias calculation
writeByte(MPU6050_ADDRESS, USER_CTRL, 0x40); // Enable FIFO
writeByte(MPU6050_ADDRESS, FIFO_EN, 0x78); // Enable gyro and accelerometer sensors for FIFO (max size 1024 bytes in MPU-6050)
}

Question : Teensy 3.1 *2 more power than >> Stm32F401

Dear Kris

Please, reading your information, about clock speed .... ok for this in consumption..
Ok...

But i miss something where Teensy 3.1 might be twice the STM32F401 : 24MHZ is not 16MHZ .. and after you say the stm32 is running in 42 Mhz ... it might not run at 16Mhz (unfortunately may be and not yet ..)

So if teensy 3.1 is running at 24Mhz and Stm32F401 at 42Mhz (minimum real ?), why Teensy3.1 is twice more than STM32 ?

Of course STM32 is looking better at first as you reach
"
5500 Hz update rate on a 3.3 V 84 MHz STM32F401
and
3200 Hz update rate on a 3.3 V 96 MHz Teensy 3.1
"
It looks already twice better for STM32F : 5500/3200 = 1.7 .... at maximun speed ( and may be "closed to maximum core power" not exactly....)

But if STM32F can not slow down to 16Mhz and stay at 42 Mhz ....

Why Teensy 3.1 (24Mhz) is always twice worst than STM32F(42Mhz minimum for now, 16Mhz expected) ?

Based on update rate at full speed, what are CPU specs for Teensy 3.1 and STM32F401 ? May be you could really measure it on both card ?

Why not also using DragonFly on STM32L401 also to reduce power consumption ?

..... If stm32 can NOT be so slow down, why is better ? If Teensy 3.1 can slow down ....

Keep going on your projects...
Best regards
J

Comsuption

Hi,

Do you know the électrical consumption of your STM32F401 and MPU6050 at 5.5kHz ?

Best,
Cédric

Calibration question

Hi Kris,

I have a general magnetometer calibration question for you;

When applying the hard iron offset bias to the raw x,y,z values of the magnetometer, is the offset always subtracted from the raw data, regardless of if the offset is negative or not?

Using your calibration wiki as an example, I can see you calculate an offset bias of -406.09, 3.46, and -121.55 for x, y, and z respectively. Then, you subtract 406.09, 3.46, and 121.55 from the raw values.

When i started calculating the offset bias for my own magnetometer, i got values of 13.165, 21.21, and -36.125 for x, y, and z respectively. However, when i subtracted these bias' from my raw values, the plotted graph points moved even further away from the origin for My/Mz and Mx/Mz.

I suspected that this was because I was subtracting 36.125 from my raw z values, when instead i should have been subtracting -36.125 (i.e adding, because it's negative). Using this as the new z offset bias produced more expected results, with graph points plotted in a sphere around the origin.

So, my question is, it seems to me that if i calculate a negative value for the hard iron offset bias, i should be adding it to the raw values instead of subtracting it, however, in your example you do not do this, you just subtract the number from the raw. Could you clarify what the right thing to do is? I am new to sensor calibration, so i really do not know if what i'm doing is correct.

Thanks in advance, appreciate all the info you have put up around this topic, it's very helpful.

Magnetometer calibration expected result could not achieved

Hey Kris,

First of all, many thanks for sharing your work and knowledge about the IMU sesnor fusion.
i'm hoping to get your advice about an issue i'm dealing when calibration the mpu9250 magnetometer.

As i'm developing an application based on the MPU9250 i used your magnetometer calibration routine as shown and explained here:
https://github.com/kriswiner/MPU6050/wiki/Simple-and-Effective-Magnetometer-Calibration

my Issue is that i cant meet the expected result after calibrating the magnetometer data, i'm getting ellipsoid centered around 0,0 (photos attached).

i read here in some issue comments about the importance of the rotation of the sensor while collecting the data. i used tera-term to collect the mag adc values, and then preforming the calibration on the recorded data. i collected the data very carefully and kept rotating the sensor in sphere 3D shape, steady as i can.

the result are:

plotting the ADC values as is:
raw_data

plotting the values after hard iron offset removal:
after_hard_iron_removal

plotting the values after hard iron offset removal and soft iron removal:
fully_calibrated

as i get nice ellipses i suspect that the soft iron offset is not handled well.
the code used to find the scale value for the soft iron calibration:

double temp_scale[3] = {0};

 mag_scale[0]  = (mag_max[0] - mag_min[0])/2;
 mag_scale[1]  = (mag_max[1] - mag_min[1])/2;
 mag_scale[2]  = (mag_max[2] - mag_min[2])/2;

 qDebug() << "Mag bias applied on all vectors done!";
 double avg_rad = mag_scale[0] + mag_scale[1] + mag_scale[2];
 avg_rad /= 3.0;

 temp_scale[0] = avg_rad/mag_scale[0];
 temp_scale[1] = avg_rad/mag_scale[1];
 temp_scale[2] = avg_rad/mag_scale[2];


 for(ii = 0; ii < m_x.size() ; ii++)
 {
   // x axis
   m_x[ii] *= temp_scale[0];
 }
 for(ii = 0; ii < m_y.size() ; ii++)
 {
   // y axis
   m_y[ii] *= temp_scale[1];
 }
 for(ii = 0; ii < m_z.size() ; ii++)
 {
   // z axis
   m_z[ii] *= temp_scale[2];
 } 

Many Thanks in advance!
David

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.