Possible bug in HMC5883 code

This forum is dedicated to software development related to MultiWii.
It is not the right place to submit a setup problem.
Software download
Post Reply
pm1
Posts: 136
Joined: Sun Jan 22, 2012 7:26 pm

Possible bug in HMC5883 code

Post by pm1 »

The calibration with the internal test mode of HMC5883 works (at least with my 2 different boards) not as expected:

Code: Select all

   #if defined(HMC5883)
      magCal[ROLL]  =  1160.0 / abs(magADC[ROLL]);
      magCal[PITCH] =  1160.0 / abs(magADC[PITCH]);
      magCal[YAW]   =  1080.0 / abs(magADC[YAW]);
 

magADC for the different axis should here deliver values about 700. The actual values were about 1100. Therefore the following line is not processed correctly, since the measure 1100 are correct for the default configuration gain of 1.3 Ga:
i2c_writeReg(MAG_ADDRESS ,0x01 ,0x60 ); //Configuration Register B -- 011 00000 configuration gain 2.5Ga

I now introduced a 50 ms delay after that command, then I could read the expected values (I don't know, why this has to be put in, and why the delay must be such big)

Code: Select all

    ..
    i2c_writeReg(MAG_ADDRESS ,0x01 ,0x60 ); //Configuration Register B  -- 011 00000    configuration gain 2.5Ga
     delay(50);
    // force positiveBias
    i2c_writeReg(MAG_ADDRESS ,0x00 ,0x71 ); //Configuration Register A  -- 0 11 100 01  num samples: 8 ; output rate: 15Hz ; positive bias
    ..

and here:

Code: Select all

    ...
    i2c_writeReg(MAG_ADDRESS ,0x01 ,0x20 ); //Configuration Register B  -- 001 00000    configuration gain 1.3Ga
    delay(50);
    i2c_writeReg(MAG_ADDRESS ,0x00 ,0x70 ); //Configuration Register A  -- 0 11 100 00  num samples: 8 ; output rate: 15Hz ; normal measurement mode
    i2c_writeReg(MAG_ADDRESS ,0x02 ,0x00 ); //Mode register             -- 000000 00    continuous Conversion Mode
    ...


This code works for me.

There is another not so fine code here:
magCal[ROLL] = 1160.0 / abs(magADC[ROLL]);
magCal[PITCH] = 1160.0 / abs(magADC[PITCH]);
magCal[YAW] = 1080.0 / abs(magADC[YAW]);

The different factor of 1080 has to be applied to the physical axis of the chip, not to the logical axis of the copter (define MAG_ORIENTATION has bee applied already). I didn't find a easy solution for this, but I think it's not so relevant, since it only leads to a problem when the chip is mounted vertically ;) .

timecop
Posts: 1880
Joined: Fri Sep 02, 2011 4:48 pm

Re: Possible bug in HMC5883 code

Post by timecop »

Very interesting!

Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

Re: Possible bug in HMC5883 code

Post by Alexinparis »

Hi,

I try to understand: according to your code, configuring register B must be configured before register A otherwise is doesn't work as expected ?

About the magCal axis problem, yes you are true.
It's not so easy to handle this properly in the code.
Hopefully ROLL&PITCH can be switched without problem, and the YAW axis should remain the same as long as the sensor is mounting in a flat position.

pm1 wrote:The calibration with the internal test mode of HMC5883 works (at least with my 2 different boards) not as expected:

Code: Select all

   #if defined(HMC5883)
      magCal[ROLL]  =  1160.0 / abs(magADC[ROLL]);
      magCal[PITCH] =  1160.0 / abs(magADC[PITCH]);
      magCal[YAW]   =  1080.0 / abs(magADC[YAW]);
 

magADC for the different axis should here deliver values about 700. The actual values were about 1100. Therefore the following line is not processed correctly, since the measure 1100 are correct for the default configuration gain of 1.3 Ga:
i2c_writeReg(MAG_ADDRESS ,0x01 ,0x60 ); //Configuration Register B -- 011 00000 configuration gain 2.5Ga

I now introduced a 50 ms delay after that command, then I could read the expected values (I don't know, why this has to be put in, and why the delay must be such big)

Code: Select all

    ..
    i2c_writeReg(MAG_ADDRESS ,0x01 ,0x60 ); //Configuration Register B  -- 011 00000    configuration gain 2.5Ga
     delay(50);
    // force positiveBias
    i2c_writeReg(MAG_ADDRESS ,0x00 ,0x71 ); //Configuration Register A  -- 0 11 100 01  num samples: 8 ; output rate: 15Hz ; positive bias
    ..

and here:

Code: Select all

    ...
    i2c_writeReg(MAG_ADDRESS ,0x01 ,0x20 ); //Configuration Register B  -- 001 00000    configuration gain 1.3Ga
    delay(50);
    i2c_writeReg(MAG_ADDRESS ,0x00 ,0x70 ); //Configuration Register A  -- 0 11 100 00  num samples: 8 ; output rate: 15Hz ; normal measurement mode
    i2c_writeReg(MAG_ADDRESS ,0x02 ,0x00 ); //Mode register             -- 000000 00    continuous Conversion Mode
    ...


This code works for me.

There is another not so fine code here:
magCal[ROLL] = 1160.0 / abs(magADC[ROLL]);
magCal[PITCH] = 1160.0 / abs(magADC[PITCH]);
magCal[YAW] = 1080.0 / abs(magADC[YAW]);

The different factor of 1080 has to be applied to the physical axis of the chip, not to the logical axis of the copter (define MAG_ORIENTATION has bee applied already). I didn't find a easy solution for this, but I think it's not so relevant, since it only leads to a problem when the chip is mounted vertically ;) .

timecop
Posts: 1880
Joined: Fri Sep 02, 2011 4:48 pm

Re: Possible bug in HMC5883 code

Post by timecop »

The point is adding delay, I think.
Here's the relevant bit from the datasheet:

This writes the 00 into the second register or mode register to switch from single to continuous measurement mode setting. With the data rate at the factory default of 15Hz updates, a 67 milli-second typical delay should be allowed by the I2C master before querying the HMC5883L data registers for new measurements.

pm1
Posts: 136
Joined: Sun Jan 22, 2012 7:26 pm

Re: Possible bug in HMC5883 code

Post by pm1 »

I try to understand: according to your code, configuring register B must be configured before register A otherwise is doesn't work as expected ?

No, but after configuring Register B, there must be a delay

Here's the relevant bit from the datasheet: ...


The datasheet says, you`ll have to have a delay after configuration of the mode register and reading the data register. There is already a sufficient delay at that point. The delay I had to introduce is between two configuration registers...

... The main reason for the code change is, the self test with 1.3Ga instead of 2.5Ga leads to an overflow on the sensor at one of my boards...

timecop
Posts: 1880
Joined: Fri Sep 02, 2011 4:48 pm

Re: Possible bug in HMC5883 code

Post by timecop »

I'm not sure delay between register writes is valid.
you are able to write all 3 values at once :

ex. 3c cfa cfb mode and it should work according to datasheet.
its also a bit annoying that mwc code uses magic constants instead of verbose bit masks for the register settings.

pm1
Posts: 136
Joined: Sun Jan 22, 2012 7:26 pm

Re: Possible bug in HMC5883 code

Post by pm1 »

I'm not sure delay between register writes is valid.

I think, it's not a question of valid. I agree, there is no reason according to the datasheet why the registers should not be written at once, but I find no reason, why there shouldn't be a delay between them.

Reality is, if there is only a small delay of two consecutive write operations, the configuration doesn't work as expected.

timecop
Posts: 1880
Joined: Fri Sep 02, 2011 4:48 pm

Re: Possible bug in HMC5883 code

Post by timecop »

Have you tried writing the registers all at once, i.e. how the datasheet recommends?

3C+W | subaddr ( 0 ) | CfgA CfgB Mode | Stop

pm1
Posts: 136
Joined: Sun Jan 22, 2012 7:26 pm

Re: Possible bug in HMC5883 code

Post by pm1 »

I tried now :
i2c_rep_start(MAG_ADDRESS<<1); // I2C write direction
i2c_write(0); // register selection
i2c_write(0x71); // value to write in register
i2c_write(0x60); // value to write in register
i2c_write(0x01); // value to write in register
i2c_stop();

It does not work.

I looked again into the data sheet. In my opinion it says, you may use this way, but even the operation example shows only a single register change.

pm1
Posts: 136
Joined: Sun Jan 22, 2012 7:26 pm

Re: Possible bug in HMC5883 code

Post by pm1 »

Ok, one step further...
It seems to be, that the chip is not correctly initialized somehow. On my boards the reaction was even different after power on or reset.
The result is, the first configuration, you send to the chip does not work correctly. I now send a dummy configuration at first. After that, everything works.

Code: Select all

  void Mag_init() { 
    // First time initalization is a dummy, does not work
    i2c_writeReg(MAG_ADDRESS ,0x00 ,0x70 ); //Configuration Register A  -- 0 11 100 01  num samples: 8 ; output rate: 15Hz
    i2c_writeReg(MAG_ADDRESS ,0x01 ,0x60 ); //Configuration Register B  -- 011 00000    configuration gain 2.5Ga
    i2c_writeReg(MAG_ADDRESS ,0x02 ,0x01 ); //Mode register             -- 000000 01    single Conversion Mode
   delay(70);
    // now real initialization
    i2c_writeReg(MAG_ADDRESS ,0x00 ,0x71 ); //Configuration Register A  -- 0 11 100 01  num samples: 8 ; output rate: 15Hz ; positive bias
    i2c_writeReg(MAG_ADDRESS ,0x01 ,0x60 ); //Configuration Register B  -- 011 00000    configuration gain 2.5Ga
    i2c_writeReg(MAG_ADDRESS ,0x02 ,0x01 ); //Mode register             -- 000000 01    single Conversion Mode
    // read values from the compass -  self test operation
    // by placing the mode register into single-measurement mode (0x01), two data acquisition cycles will be made on each magnetic vector.
    // The first acquisition values will be subtracted from the second acquisition, and the net measurement will be placed into the data output registers
    delay(150);
    getADC();

      #if defined(HMC5883)
...
Last edited by pm1 on Sat Sep 29, 2012 3:51 pm, edited 1 time in total.

timecop
Posts: 1880
Joined: Fri Sep 02, 2011 4:48 pm

Re: Possible bug in HMC5883 code

Post by timecop »

According to datasheet, chip is ready for I2C commands within 200us, but for measurement reading within 50ms.
Could it be because of that? How quick after power up does this calibration occur? Within the first 50ms perhaps?

pm1
Posts: 136
Joined: Sun Jan 22, 2012 7:26 pm

Re: Possible bug in HMC5883 code

Post by pm1 »

That was my guess, too. But I did put in a delay before calibration, -> no success...

esamolocik
Posts: 10
Joined: Fri Sep 28, 2012 11:45 pm

Re: Possible bug in HMC5883 code

Post by esamolocik »

Hi Guys,

I seem to have a problem with HMC5883 magnetometer calibration with multiwii software 2.1.
Till now I was using version 1.9 and all worked fine - I was able to calibrate the compass without any problems.
Now after upgrading and before calibration i see odd values like:
Roll: 5000
Pitch: 5000
Yaw: -2477 - 2837

Calibration doesn't help and Roll, Pitch, Yaw constantly changes from + to - with strange values. even if not moving.

I tried pointed out in this thread code change and sometimes after restart I see small values like 1, 100, 400 but after another restart once again values as highlighted above.
Sometimes after restart either roll or pitch show a value of 0 and there are no readings.
On another restart all readings can be 5000.

I assume that this is an initialization bug.

I rolled back to 1.9 software and all works fine. Any hints?

pm1
Posts: 136
Joined: Sun Jan 22, 2012 7:26 pm

Re: Possible bug in HMC5883 code

Post by pm1 »

Most likely you ran into the overflow I described in this thread. Have you already tried this fix?

viewtopic.php?f=8&t=2253#p21094

esamolocik
Posts: 10
Joined: Fri Sep 28, 2012 11:45 pm

Re: Possible bug in HMC5883 code

Post by esamolocik »

pm1 wrote:Most likely you ran into the overflow I described in this thread. Have you already tried this fix?

viewtopic.php?f=8&t=2253#p21094


Yes, I tried this code and still no luck.
Actually what I described above is after making pointed out by you code.

pm1
Posts: 136
Joined: Sun Jan 22, 2012 7:26 pm

Re: Possible bug in HMC5883 code

Post by pm1 »

esamolocik wrote:Yes, I tried this code and still no luck.
Actually what I described above is after making pointed out by you code.


// leave test mode
i2c_writeReg(MAG_ADDRESS ,0x00 ,0x70 ); //Configuration Register A -- 0 11 100 00 num samples: 8 ; output rate: 15Hz ; normal measurement mode
i2c_writeReg(MAG_ADDRESS ,0x01 ,0x40 ); //Configuration Register B -- 001 00000 configuration gain 1.3Ga
i2c_writeReg(MAG_ADDRESS ,0x02 ,0x00 ); //Mode register -- 000000 00 continuous Conversion Mode

Change value marked red...

Maybe give that a try. There seem to be overflows...

esamolocik
Posts: 10
Joined: Fri Sep 28, 2012 11:45 pm

Re: Possible bug in HMC5883 code

Post by esamolocik »

I tried mentioned change but still the same.
The Values of magnetometer still oscillate at 3-5 thousand and change when i move.
Any more hints?

Not sure if this helps but this is how mag entry looked in 1.9:

Code: Select all

#if defined(HMC5843) || defined(HMC5883)
void Mag_init() {
  delay(100);
  i2c_writeReg(0X3C ,0x02 ,0x00 ); //register: Mode register  --  value: Continuous-Conversion Mode
}

void Device_Mag_getADC() {
  i2c_getSixRawADC(0X3C,0X03);
  #if defined(HMC5843)
    MAG_ORIENTATION( ((rawADC[0]<<8) | rawADC[1]) ,
                     ((rawADC[2]<<8) | rawADC[3]) ,
                    -((rawADC[4]<<8) | rawADC[5]) );
  #endif
  #if defined (HMC5883)
    MAG_ORIENTATION( ((rawADC[4]<<8) | rawADC[5]) ,
                    -((rawADC[0]<<8) | rawADC[1]) ,
                    -((rawADC[2]<<8) | rawADC[3]) );
  #endif
}
#endif

pm1
Posts: 136
Joined: Sun Jan 22, 2012 7:26 pm

Re: Possible bug in HMC5883 code

Post by pm1 »

Not immediately,
but for debug: insert the following:

magCal[YAW] = 1000.0 / abs(magADC[YAW]);
#endif

debug[0] = magADC[ROLL];
debug[1] = magADC[PITCH];
debug[2] = magADC[YAW];

// leave test mode

Please give the values of the debug values in the gui...

esamolocik
Posts: 10
Joined: Fri Sep 28, 2012 11:45 pm

Re: Possible bug in HMC5883 code

Post by esamolocik »

Debug values in GUI are as follows:
-1
-1
-2

After another reset they change to:
0
-1
0
(Here Roll and Yaw don change and have values 0 and 57)

After another:
-1
-1
-1
(And here all the values change very quickly between -5000 and 5000)

pm1
Posts: 136
Joined: Sun Jan 22, 2012 7:26 pm

Re: Possible bug in HMC5883 code

Post by pm1 »

Ok,
I have no explanation, maybe a workaround:
old
magCal[ROLL] = 1160.0 / abs(magADC[ROLL]);
magCal[PITCH] = 1160.0 / abs(magADC[PITCH]);
magCal[YAW] = 1080.0 / abs(magADC[YAW]);
new
magCal[ROLL] = 1160.0;
magCal[PITCH] = 1160.0;
magCal[YAW] = 1080.0;

In fact removing calibration, more or less like in 1.9...

esamolocik
Posts: 10
Joined: Fri Sep 28, 2012 11:45 pm

Re: Possible bug in HMC5883 code

Post by esamolocik »

Still didn't help.
Same odd readings -5000 to 5000
:/

pm1
Posts: 136
Joined: Sun Jan 22, 2012 7:26 pm

Re: Possible bug in HMC5883 code

Post by pm1 »

And after calibration?

esamolocik
Posts: 10
Joined: Fri Sep 28, 2012 11:45 pm

Re: Possible bug in HMC5883 code

Post by esamolocik »

I have once again taken original 2.1 code and only made highlighted changes
magCal[ROLL] = 1160.0;
magCal[PITCH] = 1160.0;
magCal[YAW] = 1080.0;

Still no luck even after calibration :/

The code looks now as below. Let me know if I can try out any changes.:

Code: Select all

#if defined(HMC5843) || defined(HMC5883)
  #define MAG_ADDRESS 0x1E
  #define MAG_DATA_REGISTER 0x03
 
  void Mag_init() {
    delay(100);
    // force positiveBias
    i2c_writeReg(MAG_ADDRESS ,0x00 ,0x71 ); //Configuration Register A  -- 0 11 100 01  num samples: 8 ; output rate: 15Hz ; positive bias
    delay(50);
    // set gains for calibration
    i2c_writeReg(MAG_ADDRESS ,0x01 ,0x60 ); //Configuration Register B  -- 011 00000    configuration gain 2.5Ga
    i2c_writeReg(MAG_ADDRESS ,0x02 ,0x01 ); //Mode register             -- 000000 01    single Conversion Mode

    // read values from the compass -  self test operation
    // by placing the mode register into single-measurement mode (0x01), two data acquisition cycles will be made on each magnetic vector.
    // The first acquisition values will be subtracted from the second acquisition, and the net measurement will be placed into the data output registers
    delay(100);
      getADC();
    delay(10);
    #if defined(HMC5883)
      magCal[ROLL]  =  1160.0;
      magCal[PITCH] =  1160.0;
      magCal[YAW]   =  1080.0;
    #else
      magCal[ROLL]  =  1000.0 / abs(magADC[ROLL]);
      magCal[PITCH] =  1000.0 / abs(magADC[PITCH]);
      magCal[YAW]   =  1000.0 / abs(magADC[YAW]);
    #endif

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

    magInit = 1;
  }


Btw, on multiwii 1.9 Mag readings are good and I'm able to calibrate the sensor. Here Roll, Pitch, Yaw values are within -200 to 200(more or less).
Also in GUI, quad model that simulates the movement works as expected.

pm1
Posts: 136
Joined: Sun Jan 22, 2012 7:26 pm

Re: Possible bug in HMC5883 code

Post by pm1 »

Sorry,
my last suggestion was crap. Try to replace ini with this:

void Mag_init() {
delay(100);

magCal[ROLL] = 1.16;
magCal[PITCH] = 1.16;
magCal[YAW] = 1.08;
i2c_writeReg(MAG_ADDRESS ,0x02 ,0x00 ); //Mode register -- 000000 00 continuous Conversion Mode

magInit = 1;
}

esamolocik
Posts: 10
Joined: Fri Sep 28, 2012 11:45 pm

Re: Possible bug in HMC5883 code

Post by esamolocik »

pm1 wrote:Sorry,
my last suggestion was crap. Try to replace ini with this:

void Mag_init() {
delay(100);

magCal[ROLL] = 1.16;
magCal[PITCH] = 1.16;
magCal[YAW] = 1.08;
i2c_writeReg(MAG_ADDRESS ,0x02 ,0x00 ); //Mode register -- 000000 00 continuous Conversion Mode

magInit = 1;
}


It works :)
I have proper readings + I'm able to calibrate the mag.

So having above, what limitation are there comparing to what's in code 2.1?

pm1
Posts: 136
Joined: Sun Jan 22, 2012 7:26 pm

Re: Possible bug in HMC5883 code

Post by pm1 »

The calibration is now not temperature compensated. You might have to recalibrate mag from time to time, if using gps or maybe headfree mode....

But I have not asked, which board do you have (or which IMU). It seems, that the test mode of the mag sensor is not working at all at your board...

esamolocik
Posts: 10
Joined: Fri Sep 28, 2012 11:45 pm

Re: Possible bug in HMC5883 code

Post by esamolocik »

I use flowing board:
http://multiwiicopter.pl/ (unfortunately the site is in Polish)

It uses MEGA 382P Mini Pro 16MHz 5V processor, ITG-3200 gyro, BMA180 Acc and of course HMC5883L Mag.

One thing that I didn't highlight is that mag is not on the board and is placed on an external board to eliminate any magnetic interference from the electronics.

Is there a chance to enable a code with temp compensation?

pm1
Posts: 136
Joined: Sun Jan 22, 2012 7:26 pm

Re: Possible bug in HMC5883 code

Post by pm1 »

mhhhhh, I looked into the data sheet... Your reading would eventually make sense, if someone has forgotten a capacitor between pin 8 and 12 of the chip. (Just a guess, might be completely wrong).

esamolocik
Posts: 10
Joined: Fri Sep 28, 2012 11:45 pm

Re: Possible bug in HMC5883 code

Post by esamolocik »

pm1 wrote:mhhhhh, I looked into the data sheet... Your reading would eventually make sense, if someone has forgotten a capacitor between pin 8 and 12 of the chip. (Just a guess, might be completely wrong).


Hmm, you mean on the Mag chip? I can take a look at this. What type of capacitor this should be?

pm1
Posts: 136
Joined: Sun Jan 22, 2012 7:26 pm

Re: Possible bug in HMC5883 code

Post by pm1 »

Yes, 0.22 uF

esamolocik
Posts: 10
Joined: Fri Sep 28, 2012 11:45 pm

Re: Possible bug in HMC5883 code

Post by esamolocik »

Thanks pm1 for your great support!
For time being I have at least a workaround.

Btw, is this a normal practice to put a capacitor in mentioned place?
(I'm not a good in electronics but know how to solder :))

pm1
Posts: 136
Joined: Sun Jan 22, 2012 7:26 pm

Re: Possible bug in HMC5883 code

Post by pm1 »

esamolocik wrote:Thanks pm1 for your great support!
For time being I have at least a workaround.

Btw, is this a normal practice to put a capacitor in mentioned place?
(I'm not a good in electronics but know how to solder :))


The capacitor should be somewhere on the board. It *has* to be between pin 8 and 12 of the baro chip according to the data sheet (download it and have a look)...

timecop
Posts: 1880
Joined: Fri Sep 02, 2011 4:48 pm

Re: Possible bug in HMC5883 code

Post by timecop »

You mean mag chip.
I'm pretty sure setp/setc cap is NOT optional, since its the cap for set/reset strap which is pulsed before each measurement (test mode or not).

pm1
Posts: 136
Joined: Sun Jan 22, 2012 7:26 pm

Re: Possible bug in HMC5883 code

Post by pm1 »

timecop wrote:You mean mag chip.
I'm pretty sure setp/setc cap is NOT optional, since its the cap for set/reset strap which is pulsed before each measurement (test mode or not).


You probably are right. But that was the only idea I had, that test mode outputs a differential vaule near 0, and normal measurements do output at least something...

inrotation
Posts: 1
Joined: Mon Oct 29, 2012 4:27 pm

Re: Possible bug in HMC5883 code

Post by inrotation »

Hi guys, i just want to give a big thank you to pm1 for this fix. last year in november when it was realy hard to get a free IMU, i bought a 10DOF IMU from an ebay seller who's located in Litavia (i think). for some reasons i dont use the board til now, and guess what? i run in the same problems that esamolocik had, the MAG displays values around +-5000 and the compass needle is flipping like hell if you move the copter for 2-3 degrees. i tried V2.1 and 2.11_dev1177, but no luck. after a lot of searching i stumbled up on your solution and the MAG is working great now.
i attached a picture of the IMU, i can see there is soldered something to pin 8 of the HMC5883 but i cannot identify what it is and if it is connected to pin 12. i will check this if i disassemble the copter next time.

anyhow thank you again for helping me out :).
Attachments
10DOF csg_extreme IMU
10DOF csg_extreme IMU

Post Reply