Pro Micro 5V and QMC5883

I love the little Sparkfun Pro Micro 5V. I loaded MultiWii 2.3 onto it. I have an MPU6050 and burned out my HMC5883 magnetometer. I couldnt find an HMC5883 so resorted to the China Junk QMC5883 which they claim is under license from Honeywell. Great, but it is not the same chip.

I found some code on Arduino which gets me x,y,z out of the sensor but it is about 100 x magnitude compared to the Honeywell HMC5883.

The problem is how do I calibrate it and scale the values in MultiWii? I used the QMC5883 library examples and got 6 values for calibration, but when I try to use their compass.setCalibration(x, x, y, y, z, z) function, I get an error that says no function setCalibration(int, int, int, int, int). That’s right, it seems to expect 5 integer values and not 6. This is why I hate Chinese knockoff junk even if it is licensed.

Here’s the code from MultiWii where it gets the magnetometer data.

// ************************************************************************************************************
// I2C Compass HMC5883
// ************************************************************************************************************
// I2C adress: 0x3C (8bit)   0x1E (7bit)
// ************************************************************************************************************

#if defined(HMC5883)

#define HMC58X3_R_CONFA 0
#define HMC58X3_R_CONFB 1
#define HMC58X3_R_MODE 2
#define HMC58X3_X_SELF_TEST_GAUSS (+1.16)                       //!< X axis level when bias current is applied.
#define HMC58X3_Y_SELF_TEST_GAUSS (+1.16)   //!< Y axis level when bias current is applied.
#define HMC58X3_Z_SELF_TEST_GAUSS (+1.08)                       //!< Y axis level when bias current is applied.
#define SELF_TEST_LOW_LIMIT  (243.0/390.0)   //!< Low limit when gain is 5.
#define SELF_TEST_HIGH_LIMIT (575.0/390.0)   //!< High limit when gain is 5.
#define HMC_POS_BIAS 1
#define HMC_NEG_BIAS 2

#define MAG_ADDRESS 0x0D//0x1E
#define MAG_DATA_REGISTER 0x00//0x03

void Mag_init() {
  int32_t xyz_total[3]={0,0,0};  // 32 bit totals so they won't overflow.
  bool bret=true;                // Error indicator

  delay(50);  //Wait before start
  i2c_writeReg(MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_POS_BIAS); // Reg A DOR=0x010 + MS1,MS0 set to pos bias

  // Note that the  very first measurement after a gain change maintains the same gain as the previous setting. 
  // The new gain setting is effective from the second measurement and on.

  i2c_writeReg(MAG_ADDRESS, HMC58X3_R_CONFB, 2 << 5);  //Set the Gain
  i2c_writeReg(MAG_ADDRESS,HMC58X3_R_MODE, 1);
  delay(100);
  getADC();  //Get one sample, and discard it

  for (uint8_t i=0; i<10; i++) { //Collect 10 samples
    i2c_writeReg(MAG_ADDRESS,HMC58X3_R_MODE, 1);
    delay(100);
    getADC();   // Get the raw values in case the scales have already been changed.
                
    // Since the measurements are noisy, they should be averaged rather than taking the max.
    xyz_total[0]+=imu.magADC[0];
    xyz_total[1]+=imu.magADC[1];
    xyz_total[2]+=imu.magADC[2];
                
    // Detect saturation.
    if (-(1<<12) >= min(imu.magADC[0],min(imu.magADC[1],imu.magADC[2]))) {
      bret=false;
      break;  // Breaks out of the for loop.  No sense in continuing if we saturated.
    }
  }

  // Apply the negative bias. (Same gain)
  i2c_writeReg(MAG_ADDRESS,HMC58X3_R_CONFA, 0x010 + HMC_NEG_BIAS); // Reg A DOR=0x010 + MS1,MS0 set to negative bias.
  for (uint8_t i=0; i<10; i++) { 
    i2c_writeReg(MAG_ADDRESS,HMC58X3_R_MODE, 1);
    delay(100);
    getADC();  // Get the raw values in case the scales have already been changed.
                
    // Since the measurements are noisy, they should be averaged.
    xyz_total[0]-=imu.magADC[0];
    xyz_total[1]-=imu.magADC[1];
    xyz_total[2]-=imu.magADC[2];

    // Detect saturation.
    if (-(1<<12) >= min(imu.magADC[0],min(imu.magADC[1],imu.magADC[2]))) {
      bret=false;
      break;  // Breaks out of the for loop.  No sense in continuing if we saturated.
    }
  }

  magGain[0]=fabs(820.0*HMC58X3_X_SELF_TEST_GAUSS*2.0*10.0/xyz_total[0]);
  magGain[1]=fabs(820.0*HMC58X3_Y_SELF_TEST_GAUSS*2.0*10.0/xyz_total[1]);
  magGain[2]=fabs(820.0*HMC58X3_Z_SELF_TEST_GAUSS*2.0*10.0/xyz_total[2]);

  // leave test mode
  i2c_writeReg(MAG_ADDRESS ,HMC58X3_R_CONFA ,0x70 ); //Configuration Register A  -- 0 11 100 00  num samples: 8 ; output rate: 15Hz ; normal measurement mode
  i2c_writeReg(MAG_ADDRESS ,HMC58X3_R_CONFB ,0x20 ); //Configuration Register B  -- 001 00000    configuration gain 1.3Ga
  i2c_writeReg(MAG_ADDRESS ,HMC58X3_R_MODE  ,0x00 ); //Mode register             -- 000000 00    continuous Conversion Mode
  delay(100);
  magInit = 1;

  if (!bret) { //Something went wrong so get a best guess
    magGain[0] = 1.0;
    magGain[1] = 1.0;
    magGain[2] = 1.0;
  }
} //  Mag_init().
#endif

That’s how it handles a genuine HMC5883. The QMC5883 is missing some registers or something, so I cant just change a few hex addresses. Here’s the MultiWii code I found that gets me data but it needs scaled and calibrated somehow.

// ************************************************************************************************************
// I2C Compass QMC5883L
// ************************************************************************************************************
// I2C adress: 0x0D (7bit)
// ************************************************************************************************************
#if defined(QMC5883)

#define MAG_ADDRESS 0x0D
#define MAG_DATA_REGISTER 0x00

//REG CONTROL

#define MAG_CTRL_REG1 0x09
#define QMC_MODE 0xC1 // 11 00 00 01OSR=64(11); Range=2G(00); ODR=10Hz(00); MODE=Cont(01)
#define MAG_CTRL_REG2 0x0A 

void Mag_init() {
  i2c_writeReg(MAG_ADDRESS,0x0B,0x01);
  i2c_writeReg(MAG_ADDRESS,MAG_CTRL_REG1,QMC_MODE);
}


static void getADC() {
  i2c_getSixRawADC(MAG_ADDRESS,MAG_DATA_REGISTER);
  MAG_ORIENTATION( ((rawADC[1]<<8) | rawADC[0]) ,
                   ((rawADC[3]<<8) | rawADC[2]) ,
                   ((rawADC[5]<<8) | rawADC[4]) );
}

#if !defined(MPU6050_I2C_AUX_MASTER)
static void Device_Mag_getADC() {
  getADC();
}
#endif
#endif

How do I scale this data as it is collected?

I have a flightcontroller board with an mpu-6050 and genuine HMC5883. I decided to compare the data I’m getting with Multiwii loaded onto the Pro Micro and the “questionable” chips. To do that I’m using the Multiwiiconf program and just ran two instances of that, one to the known good board and the other to the Pro Micro. I took a screenshot and the Pro Micro is on the left side of the image, known good is on the right side.

So, what I’ve done is dive into Multiwii and see why I’m having problems. There is a group of #defines in the config.h file where I can explicitly define the orientation of the magnetometer. I have it set so that X,Y,Z corresponds to Roll, Pitch, Yaw. On the junk sensor breakouts X,Y,Z are marked. The magnetometer is only connected to the board by the wiring, so I can align the axes with the XYZ marked on the MPU6050 breakout. If I take the magnetometer board and flip it upside down around the X axis so the chip is facing the breadboard, then It behaves like a compass although moving 90 degrees results in more than 90 degrees indicated on the dial. If I keep it upright chip facing the sky, then the compass only indicates within a small range like maybe 45-60 degrees. This is where I think the scaling and gain make a difference.

But how do I adjust the scaling and gain when those registers are absent from this junk magnetometer chip?

I’m getting somewhere now. The MPU6050 breakout board that I have is actually a GY-521 and apparently all I had to do is uncomment the #define GY-521 in the config.h file. Roll and Pitch work fine now, just like the known good board. I’m going to dig a little into the code and try to find how that breakout orients the acc and gyro. It was not enough to define the MPU6050, so somewhere in the code it must set sensor orientation for the GY-521.

I still have work to do on the QMC5883, but the roll and pitch weirdness is gone.

Annnd, I found why the Roll and Pitch was weird. There is a board specific definition in def.h .

For a GY-521

#if defined(GY_521)
  #define MPU6050
  #define ACC_ORIENTATION(X, Y, Z)  {imu.accADC[ROLL]  = -X; imu.accADC[PITCH]  = -Y; imu.accADC[YAW]  =  Z;}
  #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] =  Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
  #undef INTERNAL_I2C_PULLUPS
#endif

I finally solved it. I dont know if this QMC5883 will be any good on a multicopter or plane. I was working on a breadboard and it wasnt until I pulled the Magnetometer off and held it that I was able to get it to stablilize enough for me to mess with it as I tilted it and the breadboard. It was probably that the only way to plug it in is 90 degrees to the MPU6050, but starting it up with the axes lined up helped get it right. In the end the orientation of the QMC5883 is X, Y, -Z and the HMC5883 is -X, -Y, -Z even though the datasheets show both packages have the same orientation. :?

To get it, I had to keep checking that this held true. If it didn’t I’d change the sign.

Z axis should be positive.

Roll X Mag Right should be positive, Left should be negative

Y Mag Pitch forward(down)should be positive, back(up) should be negative