Habe soeben die Wirkrichtungen so gut es geht kontrolliert und die scheinen zu stimmen!
Was die I2C adressen anbelangt hab ich im Vergleich zur 1.9er Unterschiede bemerkt.
Die MAG_ORIENTATION beim HMC5883 ist anders!
Ich habe sie geändert, jedoch ohne Erfolg.
Ich kopier den Sensor-Code mal unten rein auch wenn es nicht gern gesehen wird, aber vielleicht findet jemand einen Fehler.
Zuerst die funktionierende 1.9er:
// ************************************************************************************************************
// I2C Compass HMC5843 & HMC5883
// ************************************************************************************************************
// I2C adress: 0x3C (8bit) 0x1E (7bit)
// ************************************************************************************************************
#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
Und nun bei 2.0:
// ************************************************************************************************************
// I2C Compass HMC5843 & HMC5883
// ************************************************************************************************************
// I2C adress: 0x3C (8bit) 0x1E (7bit)
// ************************************************************************************************************
#if defined(HMC5843) || defined(HMC5883)
#define MAG_ADDRESS 0x3C
#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);
magCal[ROLL] = 1000.0 / abs(magADC[ROLL]);
magCal[PITCH] = 1000.0 / abs(magADC[PITCH]);
magCal[YAW] = 1000.0 / abs(magADC[YAW]);
// 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;
}
void getADC() {
i2c_getSixRawADC(MAG_ADDRESS,MAG_DATA_REGISTER);
#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[0]<<8) | rawADC[1]) ,
((rawADC[4]<<8) | rawADC[5]) ,
((rawADC[2]<<8) | rawADC[3]) );
#endif
}
#if not defined(MPU6050_EN_I2C_BYPASS)
void Device_Mag_getADC() {
getADC();
}
#endif
#endif