Capteur Centrale Inertielle MPU9250

Présentation du capteur MPU9250

Le circuit intégré MPU9250 contient :

  • Un accéléromètre (Accélération linéaire sur 3 axes)
  • Un gyroscope (Vitesse angulaire sur les 3 axes)
  • Un magnétomètre (Mesure du champ magnétique sur les 3 axes)

Ce genre de circuit est également appelé Centrale Inertielle ou nertial Measurement Unit (IMU)

Le magnétomètre est un composant à part dans le circuit MPU9250 ; à ce titre son adresse I2C est différente.
Dans le projet nous feront abstraction du magnétomètre qui demande un calibrage délicat.

mpu9250.svg

mpu9250_orientation_axes.svg

mpu9250_block_diagram.svg

Datasheet MPU9250

Datasheet Magnétomètre AK8963

MPU9250 Register Map


Driver MPU9250

Driver IMU MPU9250

mpu9250.h

/*
 * mpu9250.h
 *
 *  Created on: 19 avr. 2016
 *      Author: kerhoas
 */

#ifndef INC_MPU9250_H_
#define INC_MPU9250_H_

#include "main.h"
#include "types.h"



/**************************************************
 * 		REGISTER MAP MPU9250
 **************************************************/
#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 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_MPU9250 0x75 // Should return 0x71
#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

/***************************************************
 * 		REGISTER MAP MAGNETOMETER AK8963
 **************************************************/

#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_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

//*************************************************
#define		BYPASS_EN				0x02


#define    GYRO_FULL_SCALE_250_DPS    0x00
#define    GYRO_FULL_SCALE_500_DPS    0x08
#define    GYRO_FULL_SCALE_1000_DPS   0x10
#define    GYRO_FULL_SCALE_2000_DPS   0x18

#define    ACC_FULL_SCALE_2_G        0x00
#define    ACC_FULL_SCALE_4_G        0x08
#define    ACC_FULL_SCALE_8_G        0x10
#define    ACC_FULL_SCALE_16_G       0x18

// sample rate = gyroscope output rate/(1 + SMPLRT_DIV)
#define 	SAMPLE_RATE_DIVIDER_0	0x00	// 	Fe=1KHz
#define 	SAMPLE_RATE_DIVIDER_2	0x01	//	Fe=500Hz
#define 	SAMPLE_RATE_DIVIDER_3	0x02	//	Fe=333Hz
#define 	SAMPLE_RATE_DIVIDER_4	0x03	//	Fe=250Hz
#define 	SAMPLE_RATE_DIVIDER_5	0x04	//	Fe=200Hz

// GYROSCOPE DIGITAL LOW PASS FILTER	(CONFIG REGISTER)
#define		BANDWITH_GYRO_250_HZ	0x00
#define		BANDWITH_GYRO_184_HZ	0x01
#define		BANDWITH_GYRO_92_HZ		0x02
#define		BANDWITH_GYRO_41_HZ		0x03
#define		BANDWITH_GYRO_20_HZ		0x04
#define		BANDWITH_GYRO_10_HZ		0x05
#define		BANDWITH_GYRO_5_HZ		0x06


// ACCELEROMETER DIGITAL LOW PASS FILTER	(ACCEL2 REGISTER)
#define		BANDWITH_ACCEL_460_Hz	0x00
#define		BANDWITH_ACCEL_184_Hz	0x01
#define		BANDWITH_ACCEL_92_Hz	0x02
#define		BANDWITH_ACCEL_41_Hz	0x03
#define		BANDWITH_ACCEL_20_Hz	0x04
#define		BANDWITH_ACCEL_10_Hz	0x05
#define		BANDWITH_ACCEL_5_Hz		0x06

//==========================================================
#define 	GYRO_FULL_SCALE			GYRO_FULL_SCALE_1000_DPS
//==========================================================
#define		ACC_FULL_SCALE			ACC_FULL_SCALE_4_G
//==========================================================

#if	GYRO_FULL_SCALE == GYRO_FULL_SCALE_250_DPS
	#define		GYRO_RATIO			4
	#define		GYRO_SENSITIVITY	131		//2^15/250	in LSB/degrees/sec
#endif

#if	GYRO_FULL_SCALE == GYRO_FULL_SCALE_500_DPS
	#define		GYRO_RATIO			2
	#define		GYRO_SENSITIVITY	65
#endif

#if	GYRO_FULL_SCALE == GYRO_FULL_SCALE_1000_DPS
	#define		GYRO_RATIO			1
	#define		GYRO_SENSITIVITY	32
#endif

//==========================================================
#if	ACC_FULL_SCALE == ACC_FULL_SCALE_2_G
	#define		ACC_RATIO			8
	#define		ACCEL_SENSITIVITY	16384	//2^15/2	in LSB/G
#endif

#if	ACC_FULL_SCALE == ACC_FULL_SCALE_4_G
	#define		ACC_RATIO			4
	#define		ACCEL_SENSITIVITY	8192
#endif

#if	ACC_FULL_SCALE == ACC_FULL_SCALE_8_G
	#define		ACC_RATIO			2
	#define		ACCEL_SENSITIVITY	4096
#endif

#if	ACC_FULL_SCALE == ACC_FULL_SCALE_16_G
	#define		ACC_RATIO			1
	#define		ACCEL_SENSITIVITY	2048
#endif
//==========================================================

void mpu9250_InitMPU9250(void);
uint8_t mpu9250_WhoAmI(void);
uint8_t mpu9250_MagWhoAmI(void);
void mpu9250_Step(void);
void mpu9250_ReadAccelData(int16_t *);
void mpu9250_ReadGyroData(int16_t *);
void mpu9250_ReadMagData(int16_t *);
int16_t mpu9250_ReadTempData();
void mpu9250_ResetMPU9250();
void mpu9250_InitAK8963(float *);
void mpu9250_CalibrateMPU9250();



#endif /* INC_MPU9250_H_ */

mpu9250.c


#include "mpu9250.h"

enum Mscale {
  MFS_14BITS = 0, // 0.6 mG per LSB
  MFS_16BITS      // 0.15 mG per LSB
};

uint8_t Mscale = MFS_16BITS; // MFS_14BITS or MFS_16BITS, 14-bit or 16-bit magnetometer resolution
uint8_t Mmode = 0x06;        // Either 8 Hz 0x02) or 100 Hz (0x06) magnetometer data ODR
float aRes, gRes, mRes;      // scale resolutions per LSB for the sensors

float gyroBias[3] = {0, 0, 0};
float accelBias[3] = {0, 0, 0}; // Bias corrections for gyro and accelerometer
float magCalibration[3] = {0, 0, 0};
float magbias[3] = {0, 0, 0};  // Factory mag calibration and mag bias

static int32_t	accel_bias_int[3] = {0, 0, 0};
static int32_t  gyro_bias_int[3] = {0, 0, 0};

//================================================================
//			INIT MPU9250
//================================================================
void mpu9250_InitMPU9250()
{
	mpu9250_ResetMPU9250();
	HAL_Delay(100);
	// wake up device
	i2c1_WriteRegByte_IT(MPU9250_ADDRESS, PWR_MGMT_1, 	0x00); // Clear sleep mode bit (6), enable all sensors
	HAL_Delay(100); // Delay 100 ms for PLL to get established on x-axis gyro; should check for PLL ready interrupt
	i2c1_WriteRegByte_IT(MPU9250_ADDRESS, PWR_MGMT_1, 	0x01);  // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001
	i2c1_WriteRegByte_IT(MPU9250_ADDRESS, PWR_MGMT_2, 	0x00);
	i2c1_WriteRegByte_IT(MPU9250_ADDRESS, CONFIG, 		BANDWITH_GYRO_250_HZ); //41
	i2c1_WriteRegByte_IT(MPU9250_ADDRESS, SMPLRT_DIV, 	SAMPLE_RATE_DIVIDER_0);
	i2c1_WriteRegByte_IT(MPU9250_ADDRESS, GYRO_CONFIG, 	GYRO_FULL_SCALE_1000_DPS);
	i2c1_WriteRegByte_IT(MPU9250_ADDRESS, ACCEL_CONFIG, 	ACC_FULL_SCALE_4_G);
	i2c1_WriteRegByte_IT(MPU9250_ADDRESS, ACCEL_CONFIG2, BANDWITH_ACCEL_41_Hz);
	i2c1_WriteRegByte_IT(MPU9250_ADDRESS, INT_PIN_CFG, 	BYPASS_EN); // 0x37 0x02
}
//================================================================
//			INIT MAGNETOMETER AK8963
//================================================================
void mpu9250_InitAK8963(float * destination)
{
// First extract the factory calibration for each magnetometer axis
uint8_t rawData[3];  // x/y/z gyro calibration data stored here
i2c1_WriteRegByte_IT( AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer
HAL_Delay(10);
i2c1_WriteRegByte_IT( AK8963_ADDRESS, AK8963_CNTL, 0x0F); // Enter Fuse ROM access mode
HAL_Delay(10);
i2c1_ReadRegBuffer_IT( AK8963_ADDRESS, AK8963_ASAX,&rawData[0],3);  // Read the x-, y-, and z-axis calibration values
destination[0] =  (float)(rawData[0] - 128)/256.0f + 1.0f;   // Return x-axis sensitivity adjustment values, etc.
destination[1] =  (float)(rawData[1] - 128)/256.0f + 1.0f;
destination[2] =  (float)(rawData[2] - 128)/256.0f + 1.0f;
i2c1_WriteRegByte_IT(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer
HAL_Delay(10);
// 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
i2c1_WriteRegByte_IT(AK8963_ADDRESS, AK8963_CNTL, Mscale << 4 | Mmode); // Set magnetometer data resolution and sample ODR  // 0x0A 0x16
HAL_Delay(10);
}
//================================================================
//	GET MPU9250 DEVICE ID (Default Value : 0x71)
//================================================================
uint8_t mpu9250_WhoAmI(void)
{
	uint8_t response=0;
	i2c1_ReadRegBuffer_IT( MPU9250_ADDRESS, WHO_AM_I_MPU9250 ,&response,1);
	return response;
}
//================================================================
// 		GET MAGNETOMETER AK8963 DEVICE ID
//================================================================
uint8_t mpu9250_MagWhoAmI(void)
{
	uint8_t response=0;
	i2c1_ReadRegBuffer_IT( AK8963_ADDRESS, WHO_AM_I_AK8963 ,&response,1);
	return response;
}
//================================================================
//				STEP
//================================================================
void mpu9250_Step(void)
{
		uint8_t Buf[14];

		// ____________________________________
		// :::  accelerometer and gyroscope :::

		// Lecture de 14 Registres à partir de ACCEL_XOUT_H
		// ACCEL_XOUT_H, ACCEL_XOUT_L, ACCEL_YOUT_H, ACCEL_YOUT_L, ACCEL_ZOUT_H, ACCEL_ZOUT_L
		// TEMP_OUT_H, TEMP_OUT_L, GYRO_XOUT_H, GYRO_XOUT_L, GYRO_YOUT_H, GYRO_YOUT_L, GYRO_ZOUT_H, GYRO_ZOUT_L
		i2c1_ReadRegBuffer( MPU9250_ADDRESS,ACCEL_XOUT_H ,Buf,14);

		int16_t ax=-(Buf[0]<<8 | Buf[1]);
		int16_t ay=-(Buf[2]<<8 | Buf[3]);
		int16_t az=Buf[4]<<8 | Buf[5];

		ax=ax;	//+accel_bias_int[0];
		ay=ay;	//+accel_bias_int[1];
		az=az;	//-accel_bias_int[2];  

		int16_t gx=-(Buf[8]<<8 | Buf[9]);
		int16_t gy=-(Buf[10]<<8 | Buf[11]);
		int16_t gz=Buf[12]<<8 | Buf[13];

		gx = gx + gyro_bias_int[0];
		gy = gy + gyro_bias_int[1];
		gz = gz - gyro_bias_int[2];

		
#if USE_MAGNETOMETER
	   	//_____________________
	    // :::  Magnetometer :::
	    // Read register Status 1 and wait for the DRDY: Data Ready
	    uint8_t magStatus1=0;
	    do
	    {
	   	 i2c1_ReadRegBuffer_IT( AK8963_ADDRESS,AK8963_ST1 ,&magStatus1,1);
	    }
	    while (!(magStatus1&0x01));
	    // Read magnetometer data
	    uint8_t Mag[7];
	   	i2c1_ReadRegBuffer_IT( AK8963_ADDRESS,AK8963_XOUT_L,Mag,7);
    	int16_t mx=-(Mag[3]<<8 | Mag[2]);
    	int16_t my=-(Mag[1]<<8 | Mag[0]);
    	int16_t mz=-(Mag[5]<<8 | Mag[4]);
    	
#endif
		
  }
//================================================================
//			READ ACCELERATION
//================================================================
void mpu9250_ReadAccelData(int16_t * destination)
{
  uint8_t rawData[6];  // x/y/z accel register data stored here
  i2c1_ReadRegBuffer( MPU9250_ADDRESS, ACCEL_XOUT_H,&rawData[0],6);  // Read the six raw data registers into data array
  destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ;  // Turn the MSB and LSB into a signed 16-bit value
  destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
  destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
}
//================================================================
//			READ GYRO
//================================================================
void mpu9250_ReadGyroData(int16_t * destination)
{
  uint8_t rawData[6];  // x/y/z gyro register data stored here
  i2c1_ReadRegBuffer( MPU9250_ADDRESS, GYRO_XOUT_H, &rawData[0],6);  // Read the six raw data registers sequentially into data array
  destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ;  // Turn the MSB and LSB into a signed 16-bit value
  destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
  destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
}
//================================================================
//			READ MAGNETOMETER
//================================================================
void mpu9250_ReadMagData(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
  uint8_t magStatus1=0;
  do
  {
 	 i2c1_ReadRegBuffer_IT( AK8963_ADDRESS,AK8963_ST1 , &magStatus1,1);
  }
  while (!(magStatus1&0x01)); // wait for magnetometer data ready bit to be set

  i2c1_ReadRegBuffer_IT(AK8963_ADDRESS, AK8963_XOUT_L, &rawData[0],7);  // Read the six raw data and ST2 registers sequentially into data array
  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)(((int16_t)rawData[1] << 8) | rawData[0]);  // Turn the MSB and LSB into a signed 16-bit value
    destination[1] = (int16_t)(((int16_t)rawData[3] << 8) | rawData[2]) ;  // Data stored as little Endian
    destination[2] = (int16_t)(((int16_t)rawData[5] << 8) | rawData[4]) ;
   }
}
//================================================================
//			READ TEMPERATURE
//================================================================
int16_t mpu9250_ReadTempData()
{
  uint8_t rawData[2];  // x/y/z gyro register data stored here
  i2c1_ReadRegBuffer_IT( MPU9250_ADDRESS, TEMP_OUT_H, &rawData[0],2);  // Read the two raw data registers sequentially into data array
  return (int16_t)(((int16_t)rawData[0]) << 8 | rawData[1]) ;  // Turn the MSB and LSB into a 16-bit value
}
//================================================================
//			RESET MPU9250
//================================================================
void mpu9250_ResetMPU9250()
{
	i2c1_WriteRegByte_IT( MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
	  HAL_Delay(100);
}
//================================================================
//			CALIBRATE
//================================================================
void mpu9250_CalibrateMPU9250()
{
	int nb_mes=0;
	uint8_t Buf[14];
	int16_t ax=0, ay=0, az=0;
	int16_t gx=0, gy=0, gz=0;
	int32_t ax_acc=0, ay_acc=0, az_acc=0;
	int32_t	gx_acc=0, gy_acc=0, gz_acc=0;
	//uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data

	for(nb_mes=0 ; nb_mes < 100 ; nb_mes++)
	{
	i2c1_ReadRegBuffer_IT( MPU9250_ADDRESS,ACCEL_XOUT_H ,  Buf,14);
	ax=(int16_t)((int16_t)Buf[0]<<8 	| Buf[1]);
	ay=(int16_t)((int16_t)Buf[2]<<8 	| Buf[3]);
	az=(int16_t)((int16_t)Buf[4]<<8 	| Buf[5]);
	gx=(int16_t)((int16_t)Buf[8]<<8 	| Buf[9]);
	gy=(int16_t)((int16_t)Buf[10]<<8 	| Buf[11]);
	gz=(int16_t)((int16_t)Buf[12]<<8 	| Buf[13]);

	ax_acc=ax_acc+(int32_t)ax;
	ay_acc=ay_acc+(int32_t)ay;
	az_acc=az_acc+(int32_t)az;
	gx_acc=gx_acc+(int32_t)gx;
	gy_acc=gy_acc+(int32_t)gy;
	gz_acc=gz_acc+(int32_t)gz;

	HAL_Delay(20);
	}

	accel_bias_int[0]=ax_acc/100;
	accel_bias_int[1]=ay_acc/100;
	accel_bias_int[2]=az_acc/100;
	gyro_bias_int[0]=gx_acc/100;
	gyro_bias_int[1]=gy_acc/100;
	gyro_bias_int[2]=gz_acc/100;

	// NORMALIZATION AND PUSH INTO BIAS HARDWARE REGISTER --> DOESN'T WORK
	// Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup
	/*data[0] = (-gyro_bias_int[0]/GYRO_RATIO  >> 8) 	& 0xFF; // Divide by 4 to get 32.9 LSB per deg/s to conform to expected bias input format
	data[1] = (-gyro_bias_int[0]/GYRO_RATIO )       & 0xFF; // Biases are additive, so change sign on calculated average gyro biases
	data[2] = (-gyro_bias_int[1]/GYRO_RATIO   >> 8) & 0xFF;
	data[3] = (-gyro_bias_int[1]/GYRO_RATIO )       & 0xFF;
	data[4] = (-gyro_bias_int[2]/GYRO_RATIO   >> 8) & 0xFF;
	data[5] = (-gyro_bias_int[2]/GYRO_RATIO )       & 0xFF;*/

	// Push gyro biases to hardware registers ('works' randomly)
/*	i2c1_WriteRegByte_IT(MPU9250_ADDRESS, XG_OFFSET_H, data[0]);
	i2c1_WriteRegByte_IT(MPU9250_ADDRESS, XG_OFFSET_L, data[1]);
	i2c1_WriteRegByte_IT(MPU9250_ADDRESS, YG_OFFSET_H, data[2]);
	i2c1_WriteRegByte_IT(MPU9250_ADDRESS, YG_OFFSET_L, data[3]);
	i2c1_WriteRegByte_IT(MPU9250_ADDRESS, ZG_OFFSET_H, data[4]);
	i2c1_WriteRegByte_IT(MPU9250_ADDRESS, ZG_OFFSET_L, data[5]);*/
}

//=================================================================

void mpu9250_InitMPU9250() : Initialisation accéléromètre + gyroscope : réglage des filtres / Intervalles de mesure (résolution).
void mpu9250_InitAK8963(float * destination) : Initialisation du magnétomètre : réglage de la résolution
uint8_t mpu9250_WhoAmI(void) : Test liaison I2C accel + gyr , doit retourner 0x71
uint8_t mpu9250_MagWhoAmI(void) : Test liaison I2C magnétomètre
void mpu9250_Step(void) : Récupération de toutes les mesures
void mpu9250_ReadAccelData(int16_t * destination) : Récupération Accélérations
void mpu9250_ReadGyroData(int16_t * destination) : Récupération Vitesses Angulaires
void mpu9250_ReadMagData(int16_t * destination) : Récupération Mesures Magnétomètre
int16_t mpu9250_ReadTempData() : Récupération Température
void mpu9250_ResetMPU9250() : Reset
void mpu9250_CalibrateMPU9250() : Calibrage Accéléromètre + Gyroscope : détermination de l’erreur initiale (biais).
Cette erreur est soustraite par la suite à chaque mesure.

Intervalles des Donnés

Accéléromètre

  • Intervalle des valeurs mesurables : [-2G , +2G] / [-4G , +4G] / [-8G , +8G] / [-16G , +16G]
  • Configuration [-4G , +4G].
  • On récupère un int16, soit une valeur dans l’interalle [-32768 , 32767], représentant une accélération entre [-4G , +4G].
  • La donnée récupérée est donc à multiplier par (4.0/32768.0) pour obtenir une valeur en G.

REMARQUE : Au repos et à plat, on doit observer une accélération d’1G sur l’accéléromètre ( si l’on ne corrige pas les valeurs mesurées avec les valeurs au repos ).

Gyroscope

  • Intervalle des valeurs mesurables : [-250°/S , +250°/S] / [-500°/S , +500°/S] / [-1000°/S , +1000°/S] / [-2000°/S , +2000°/S]
  • Configuration [-1000°/S , +1000°/S]
  • On récupère un int16, soit une valeur dans l’interalle [-32768 , 32767], représentant une vitesse angulaire entre [-1000°/S , +1000°/S].
  • La donnée récupérée est donc à multiplier par (1000.0/32768.0)*(PI/180.0) pour obtenir une valeur en rad/s.

Traitement des Données

Angles d’Euler

A partir de l’intégration de la vitesse angulaire, il est possible de déduire les ‘attitudes’ d’un objet, autrement dit les angles d’Euler.

plane.svg

Matrice de Rotation Repère Body –> Repère Fixe

Il est possible d’estimer la position d’un objet dans un repère fixe à partir des données de la centrale inertielle, en calculant la matrice de rotation.

matrice_rotation.svg

$ \begin{bmatrix}r _{u}\\r _{v }\\r _{w} \end{bmatrix} = \begin{bmatrix} r _{0u}\\ r _{0v}\\ r _{0w} \end{bmatrix} + \begin{bmatrix} R11 & R12 & R13 \\ R21 & R22 & R23 \\ R31 & R32 & R33 \end{bmatrix} . \begin{bmatrix} r _{x}\\ r _{y}\\ r _{z} \end{bmatrix} $

Problème du “Gimbal Lock” (blocage de cardan)

Un premier problème se pose concernant l’utilisation des angles d’Euler directement.
En effet la superposition de deux axes de rotation entraine la perte d’un degré de liberté.

Ce problème est très bien illustré dans la vidéo suivante :

Video Euler (gimbal lock) Explained

Quaternions

Un Quaternion est un objet mathématique (avec un ensemble de propriétés) permettant de représenter le déplacement et la rotation d’un objet.

quaternions.svg

V direction du repère body

Q=[q0,q1,q2,q3] Q=\begin{bmatrix} q _{0},\\ q _{1},\\ q _{2},\\ q _{3}\\ \end{bmatrix}

Q=[cos(θ2),a.sin(θ2),b.sin(θ2),c.sin(θ2)] Q=\begin{bmatrix} cos(\frac{\theta} {2}),\\ a.sin(\frac{\theta} {2}),\\ b.sin(\frac{\theta} {2}),\\ c.sin(\frac{\theta} {2})\\ \end{bmatrix}

A chaque Te, on peut calculer la nouvelle valeur du vecteur quaternion à partir de la vitesse :

Qk+1=Qk+12.Te.Ωk.Qk Q _{k+1}=Q _{k}+ \frac{1}{2}.T _{e}.\Omega _{k}.Q _{k}

L’application de ce calcul permet d’éviter le problème du gimbal lock

Algorithme de Madgwick

Un autre problème important est à considérer dans le traitement des données de la centrale :

  • Les données du gyroscope dévient
  • Les données de l’accéléromètre sont bruitées (mais stables)

Pour des IMUs bon marché, il est invévitable de réaliser une fusion des données pour que l’accéléromètre compense le défaut du gyroscope.
Si l’utilisation d’un filtre de Kalmann est possible, il existe d’autres algorithmes (plus rapides) comme celui de Madgwick.
L’idée est de compenser l’erreur de mesure du gyroscope en modulant ses valeurs par le résultat d’une comparaison entre une estimation du champ de gravité et le champ de gravité mesuré (avec l’accéléromètre).

madgwicks_blocks.svg

code algorithme de madgwick

MadgwickAHRS.h

//=====================================================================================================
// MadgwickAHRS.h
//=====================================================================================================
//
// Implementation of Madgwick's IMU and AHRS algorithms.
// See: http://www.x-io.co.uk/node/8#open_source_ahrs_and_imu_algorithms
//
// Date			Author          Notes
// 29/09/2011	SOH Madgwick    Initial release
// 02/10/2011	SOH Madgwick	Optimised for reduced CPU load
//
//=====================================================================================================
#ifndef MadgwickAHRS_h
#define MadgwickAHRS_h


#include <math.h>

//----------------------------------------------------------------------------------------------------
// Variable declaration

extern volatile float beta;				// algorithm gain
extern volatile float q0, q1, q2, q3;	// quaternion of sensor frame relative to auxiliary frame

//---------------------------------------------------------------------------------------------------
// Function declarations

void MadgwickAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz);
void MadgwickAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float az);

#endif
//=====================================================================================================
// End of file
//=====================================================================================================

MadgwickAHRS.c

//=====================================================================================================
// MadgwickAHRS.c
//=====================================================================================================
//
// Implementation of Madgwick's IMU and AHRS algorithms.
// See: http://www.x-io.co.uk/node/8#open_source_ahrs_and_imu_algorithms
//
// Date			Author          Notes
// 29/09/2011	SOH Madgwick    Initial release
// 02/10/2011	SOH Madgwick	Optimised for reduced CPU load
// 19/02/2012	SOH Madgwick	Magnetometer measurement is normalised
//
//=====================================================================================================

//---------------------------------------------------------------------------------------------------
// Header files

#include "MadgwickAHRS.h"


//---------------------------------------------------------------------------------------------------
// Definitions

#define sampleFreq	100.0f		// sample frequency in Hz
#define betaDef		0.02f		// 2 * proportional gain

//---------------------------------------------------------------------------------------------------
// Variable definitions

volatile float beta = betaDef;								// 2 * proportional gain (Kp)
volatile float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f;	// quaternion of sensor frame relative to auxiliary frame

//---------------------------------------------------------------------------------------------------
// Function declarations

float invSqrt(float x);

//====================================================================================================
// Functions

//---------------------------------------------------------------------------------------------------
// AHRS algorithm update

void MadgwickAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz) {
	float recipNorm;
	float s0, s1, s2, s3;
	float qDot1, qDot2, qDot3, qDot4;
	float hx, hy;
	float _2q0mx, _2q0my, _2q0mz, _2q1mx, _2bx, _2bz, _4bx, _4bz, _2q0, _2q1, _2q2, _2q3, _2q0q2, _2q2q3, q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3;

	// Use IMU algorithm if magnetometer measurement invalid (avoids NaN in magnetometer normalisation)
	if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) {
		MadgwickAHRSupdateIMU(gx, gy, gz, ax, ay, az);
		return;
	}

	// Rate of change of quaternion from gyroscope
	qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz);
	qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy);
	qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx);
	qDot4 = 0.5f * (q0 * gz + q1 * gy - q2 * gx);

	// Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation)
	if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) {

		// Normalise accelerometer measurement
		recipNorm = invSqrt(ax * ax + ay * ay + az * az);
		ax *= recipNorm;
		ay *= recipNorm;
		az *= recipNorm;   

		// Normalise magnetometer measurement
		recipNorm = invSqrt(mx * mx + my * my + mz * mz);
		mx *= recipNorm;
		my *= recipNorm;
		mz *= recipNorm;

		// Auxiliary variables to avoid repeated arithmetic
		_2q0mx = 2.0f * q0 * mx;
		_2q0my = 2.0f * q0 * my;
		_2q0mz = 2.0f * q0 * mz;
		_2q1mx = 2.0f * q1 * mx;
		_2q0 = 2.0f * q0;
		_2q1 = 2.0f * q1;
		_2q2 = 2.0f * q2;
		_2q3 = 2.0f * q3;
		_2q0q2 = 2.0f * q0 * q2;
		_2q2q3 = 2.0f * q2 * q3;
		q0q0 = q0 * q0;
		q0q1 = q0 * q1;
		q0q2 = q0 * q2;
		q0q3 = q0 * q3;
		q1q1 = q1 * q1;
		q1q2 = q1 * q2;
		q1q3 = q1 * q3;
		q2q2 = q2 * q2;
		q2q3 = q2 * q3;
		q3q3 = q3 * q3;

		// Reference direction of Earth's magnetic field
		hx = mx * q0q0 - _2q0my * q3 + _2q0mz * q2 + mx * q1q1 + _2q1 * my * q2 + _2q1 * mz * q3 - mx * q2q2 - mx * q3q3;
		hy = _2q0mx * q3 + my * q0q0 - _2q0mz * q1 + _2q1mx * q2 - my * q1q1 + my * q2q2 + _2q2 * mz * q3 - my * q3q3;
		_2bx = sqrt(hx * hx + hy * hy);
		_2bz = -_2q0mx * q2 + _2q0my * q1 + mz * q0q0 + _2q1mx * q3 - mz * q1q1 + _2q2 * my * q3 - mz * q2q2 + mz * q3q3;
		_4bx = 2.0f * _2bx;
		_4bz = 2.0f * _2bz;

		// Gradient decent algorithm corrective step
		s0 = -_2q2 * (2.0f * q1q3 - _2q0q2 - ax) + _2q1 * (2.0f * q0q1 + _2q2q3 - ay) - _2bz * q2 * (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + (-_2bx * q3 + _2bz * q1) * (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + _2bx * q2 * (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz);
		s1 = _2q3 * (2.0f * q1q3 - _2q0q2 - ax) + _2q0 * (2.0f * q0q1 + _2q2q3 - ay) - 4.0f * q1 * (1 - 2.0f * q1q1 - 2.0f * q2q2 - az) + _2bz * q3 * (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + (_2bx * q2 + _2bz * q0) * (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + (_2bx * q3 - _4bz * q1) * (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz);
		s2 = -_2q0 * (2.0f * q1q3 - _2q0q2 - ax) + _2q3 * (2.0f * q0q1 + _2q2q3 - ay) - 4.0f * q2 * (1 - 2.0f * q1q1 - 2.0f * q2q2 - az) + (-_4bx * q2 - _2bz * q0) * (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + (_2bx * q1 + _2bz * q3) * (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + (_2bx * q0 - _4bz * q2) * (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz);
		s3 = _2q1 * (2.0f * q1q3 - _2q0q2 - ax) + _2q2 * (2.0f * q0q1 + _2q2q3 - ay) + (-_4bx * q3 + _2bz * q1) * (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + (-_2bx * q0 + _2bz * q2) * (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + _2bx * q1 * (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz);
		recipNorm = invSqrt(s0 * s0 + s1 * s1 + s2 * s2 + s3 * s3); // normalise step magnitude
		s0 *= recipNorm;
		s1 *= recipNorm;
		s2 *= recipNorm;
		s3 *= recipNorm;

		// Apply feedback step
		qDot1 -= beta * s0;
		qDot2 -= beta * s1;
		qDot3 -= beta * s2;
		qDot4 -= beta * s3;
	}

	// Integrate rate of change of quaternion to yield quaternion
	q0 += qDot1 * (1.0f / sampleFreq);
	q1 += qDot2 * (1.0f / sampleFreq);
	q2 += qDot3 * (1.0f / sampleFreq);
	q3 += qDot4 * (1.0f / sampleFreq);

	// Normalise quaternion
	recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3);
	q0 *= recipNorm;
	q1 *= recipNorm;
	q2 *= recipNorm;
	q3 *= recipNorm;
}

//---------------------------------------------------------------------------------------------------
// IMU algorithm update

void MadgwickAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float az) {
	float recipNorm;
	float s0, s1, s2, s3;
	float qDot1, qDot2, qDot3, qDot4;
	float _2q0, _2q1, _2q2, _2q3, _4q0, _4q1, _4q2 ,_8q1, _8q2, q0q0, q1q1, q2q2, q3q3;

	// Rate of change of quaternion from gyroscope
	qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz);
	qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy);
	qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx);
	qDot4 = 0.5f * (q0 * gz + q1 * gy - q2 * gx);

	// Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation)
	if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) {

		// Normalise accelerometer measurement
		recipNorm = invSqrt(ax * ax + ay * ay + az * az);
		ax *= recipNorm;
		ay *= recipNorm;
		az *= recipNorm;   

		// Auxiliary variables to avoid repeated arithmetic
		_2q0 = 2.0f * q0;
		_2q1 = 2.0f * q1;
		_2q2 = 2.0f * q2;
		_2q3 = 2.0f * q3;
		_4q0 = 4.0f * q0;
		_4q1 = 4.0f * q1;
		_4q2 = 4.0f * q2;
		_8q1 = 8.0f * q1;
		_8q2 = 8.0f * q2;
		q0q0 = q0 * q0;
		q1q1 = q1 * q1;
		q2q2 = q2 * q2;
		q3q3 = q3 * q3;

		// Gradient decent algorithm corrective step
		s0 = _4q0 * q2q2 + _2q2 * ax + _4q0 * q1q1 - _2q1 * ay;
		s1 = _4q1 * q3q3 - _2q3 * ax + 4.0f * q0q0 * q1 - _2q0 * ay - _4q1 + _8q1 * q1q1 + _8q1 * q2q2 + _4q1 * az;
		s2 = 4.0f * q0q0 * q2 + _2q0 * ax + _4q2 * q3q3 - _2q3 * ay - _4q2 + _8q2 * q1q1 + _8q2 * q2q2 + _4q2 * az;
		s3 = 4.0f * q1q1 * q3 - _2q1 * ax + 4.0f * q2q2 * q3 - _2q2 * ay;
		recipNorm = invSqrt(s0 * s0 + s1 * s1 + s2 * s2 + s3 * s3); // normalise step magnitude
		s0 *= recipNorm;
		s1 *= recipNorm;
		s2 *= recipNorm;
		s3 *= recipNorm;

		// Apply feedback step
		qDot1 -= beta * s0;
		qDot2 -= beta * s1;
		qDot3 -= beta * s2;
		qDot4 -= beta * s3;
	}

	// Integrate rate of change of quaternion to yield quaternion
	q0 += qDot1 * (1.0f / sampleFreq);
	q1 += qDot2 * (1.0f / sampleFreq);
	q2 += qDot3 * (1.0f / sampleFreq);
	q3 += qDot4 * (1.0f / sampleFreq);

	// Normalise quaternion
	recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3);
	q0 *= recipNorm;
	q1 *= recipNorm;
	q2 *= recipNorm;
	q3 *= recipNorm;
}

//---------------------------------------------------------------------------------------------------
// Fast inverse square-root
// See: http://en.wikipedia.org/wiki/Fast_inverse_square_root

float invSqrt(float x) {
	float halfx = 0.5f * x;
	float y = x;
	long i = *(long*)&y;
	i = 0x5f3759df - (i>>1);
	y = *(float*)&i;
	y = y * (1.5f - (halfx * y * y));
	return y;
}

//====================================================================================================
// END OF CODE
//====================================================================================================

Ce calcul met à jour le quaternion, duquel peuvent être calculées les attitudes (angles d’Euler).

madgwicks_applied.svg

Calcul de la Matrice de Rotation à Partir du Quaternion

R12=2.(q1.q2+q0.q3) R _{12} = 2.(q{ _{1}}.q{ _{2}}+q{ _{0}}.q{ _{3}} )
R22=q02+q12q22q32 R _{22} = q{ _{0}}^{2} + q{ _{1}}^{2} - q{ _{2}}^{2} - q{ _{3}}^{2}
R31=2.(q0.q1+q2.q3) R _{31} = 2.(q{ _{0}}.q{ _{1}}+q{ _{2}}.q{ _{3}})
R32=2.(q1.q3q0.q2) R _{32} = 2.(q{ _{1}}.q{ _{3}}-q{ _{0}}.q{ _{2}})
R33=q02q12q22+q32 R _{33} = q{ _{0}}^{2} - q{ _{1}}^{2} - q{ _{2}}^{2} + q{ _{3}}^{2}

Calcul des Angles d’Euler à Partir de la matrice de rotation

phi=atan2(R31,R33) phi = atan2(R_{31}, R_{33})
theta=asin(R32) theta = -asin (R_{32})
psi=atan2(R12,R22) psi = atan2(R_{12}, R_{22})

Documents Complémentaires

Invensense Sensor Introduction

Madgwick Internal Report