Basic program to obtain properly-scaled gyro, accelerometer, and magnetometer data from the MPU-9150 9-axis motion sensor. Nine-axis sensor fusion with Sebastian Madgwick's and Mahony's open-source sensor fusion filters running on an STM32F401RE Nucleo board at 84 MHz achieve sensor fusion filter update rates of ~5000 Hz. Additional info at https://github.com/kriswiner/STM32F401.

Dependencies:   ST_401_84MHZ mbed

Fork of MPU9150AHRS by Kris Winer

Committer:
onehorse
Date:
Sun Jun 29 22:48:08 2014 +0000
Revision:
0:39935bb3c1a1
Basic program to get properly-scaled gyro, accelerometer, and magnetometer data from the MPU9150 9-axis motion sensor. Sensor fusion is performed using Madgwick and Mahony open-source MARG fusion filters.

Who changed what in which revision?

UserRevisionLine numberNew contents of line
onehorse 0:39935bb3c1a1 1 #ifndef MPU9150_H
onehorse 0:39935bb3c1a1 2 #define MPU9150_H
onehorse 0:39935bb3c1a1 3
onehorse 0:39935bb3c1a1 4 #include "mbed.h"
onehorse 0:39935bb3c1a1 5
onehorse 0:39935bb3c1a1 6 // Define registers per MPU6050, Register Map and Descriptions, Rev 4.2, 08/19/2013 6 DOF Motion sensor fusion device
onehorse 0:39935bb3c1a1 7 // Invensense Inc., www.invensense.com
onehorse 0:39935bb3c1a1 8 // See also MPU-9150 Register Map and Descriptions, Revision 4.0, RM-MPU-9150A-00, 9/12/2012 for registers not listed in
onehorse 0:39935bb3c1a1 9 // above document; the MPU6050 and MPU 9150 are virtually identical but the latter has an on-board magnetic sensor
onehorse 0:39935bb3c1a1 10 //
onehorse 0:39935bb3c1a1 11 //Magnetometer Registers
onehorse 0:39935bb3c1a1 12 #define WHO_AM_I_AK8975A 0x00 // should return 0x48
onehorse 0:39935bb3c1a1 13 #define INFO 0x01
onehorse 0:39935bb3c1a1 14 #define AK8975A_ST1 0x02 // data ready status bit 0
onehorse 0:39935bb3c1a1 15 #define AK8975A_ADDRESS 0x0C<<1
onehorse 0:39935bb3c1a1 16 #define AK8975A_XOUT_L 0x03 // data
onehorse 0:39935bb3c1a1 17 #define AK8975A_XOUT_H 0x04
onehorse 0:39935bb3c1a1 18 #define AK8975A_YOUT_L 0x05
onehorse 0:39935bb3c1a1 19 #define AK8975A_YOUT_H 0x06
onehorse 0:39935bb3c1a1 20 #define AK8975A_ZOUT_L 0x07
onehorse 0:39935bb3c1a1 21 #define AK8975A_ZOUT_H 0x08
onehorse 0:39935bb3c1a1 22 #define AK8975A_ST2 0x09 // Data overflow bit 3 and data read error status bit 2
onehorse 0:39935bb3c1a1 23 #define AK8975A_CNTL 0x0A // Power down (0000), single-measurement (0001), self-test (1000) and Fuse ROM (1111) modes on bits 3:0
onehorse 0:39935bb3c1a1 24 #define AK8975A_ASTC 0x0C // Self test control
onehorse 0:39935bb3c1a1 25 #define AK8975A_ASAX 0x10 // Fuse ROM x-axis sensitivity adjustment value
onehorse 0:39935bb3c1a1 26 #define AK8975A_ASAY 0x11 // Fuse ROM y-axis sensitivity adjustment value
onehorse 0:39935bb3c1a1 27 #define AK8975A_ASAZ 0x12 // Fuse ROM z-axis sensitivity adjustment value
onehorse 0:39935bb3c1a1 28
onehorse 0:39935bb3c1a1 29 #define XGOFFS_TC 0x00 // Bit 7 PWR_MODE, bits 6:1 XG_OFFS_TC, bit 0 OTP_BNK_VLD
onehorse 0:39935bb3c1a1 30 #define YGOFFS_TC 0x01
onehorse 0:39935bb3c1a1 31 #define ZGOFFS_TC 0x02
onehorse 0:39935bb3c1a1 32 #define X_FINE_GAIN 0x03 // [7:0] fine gain
onehorse 0:39935bb3c1a1 33 #define Y_FINE_GAIN 0x04
onehorse 0:39935bb3c1a1 34 #define Z_FINE_GAIN 0x05
onehorse 0:39935bb3c1a1 35 #define XA_OFFSET_H 0x06 // User-defined trim values for accelerometer
onehorse 0:39935bb3c1a1 36 #define XA_OFFSET_L_TC 0x07
onehorse 0:39935bb3c1a1 37 #define YA_OFFSET_H 0x08
onehorse 0:39935bb3c1a1 38 #define YA_OFFSET_L_TC 0x09
onehorse 0:39935bb3c1a1 39 #define ZA_OFFSET_H 0x0A
onehorse 0:39935bb3c1a1 40 #define ZA_OFFSET_L_TC 0x0B
onehorse 0:39935bb3c1a1 41 #define SELF_TEST_X 0x0D
onehorse 0:39935bb3c1a1 42 #define SELF_TEST_Y 0x0E
onehorse 0:39935bb3c1a1 43 #define SELF_TEST_Z 0x0F
onehorse 0:39935bb3c1a1 44 #define SELF_TEST_A 0x10
onehorse 0:39935bb3c1a1 45 #define XG_OFFS_USRH 0x13 // User-defined trim values for gyroscope, populate with calibration routine
onehorse 0:39935bb3c1a1 46 #define XG_OFFS_USRL 0x14
onehorse 0:39935bb3c1a1 47 #define YG_OFFS_USRH 0x15
onehorse 0:39935bb3c1a1 48 #define YG_OFFS_USRL 0x16
onehorse 0:39935bb3c1a1 49 #define ZG_OFFS_USRH 0x17
onehorse 0:39935bb3c1a1 50 #define ZG_OFFS_USRL 0x18
onehorse 0:39935bb3c1a1 51 #define SMPLRT_DIV 0x19
onehorse 0:39935bb3c1a1 52 #define CONFIG 0x1A
onehorse 0:39935bb3c1a1 53 #define GYRO_CONFIG 0x1B
onehorse 0:39935bb3c1a1 54 #define ACCEL_CONFIG 0x1C
onehorse 0:39935bb3c1a1 55 #define FF_THR 0x1D // Free-fall
onehorse 0:39935bb3c1a1 56 #define FF_DUR 0x1E // Free-fall
onehorse 0:39935bb3c1a1 57 #define MOT_THR 0x1F // Motion detection threshold bits [7:0]
onehorse 0:39935bb3c1a1 58 #define MOT_DUR 0x20 // Duration counter threshold for motion interrupt generation, 1 kHz rate, LSB = 1 ms
onehorse 0:39935bb3c1a1 59 #define ZMOT_THR 0x21 // Zero-motion detection threshold bits [7:0]
onehorse 0:39935bb3c1a1 60 #define ZRMOT_DUR 0x22 // Duration counter threshold for zero motion interrupt generation, 16 Hz rate, LSB = 64 ms
onehorse 0:39935bb3c1a1 61 #define FIFO_EN 0x23
onehorse 0:39935bb3c1a1 62 #define I2C_MST_CTRL 0x24
onehorse 0:39935bb3c1a1 63 #define I2C_SLV0_ADDR 0x25
onehorse 0:39935bb3c1a1 64 #define I2C_SLV0_REG 0x26
onehorse 0:39935bb3c1a1 65 #define I2C_SLV0_CTRL 0x27
onehorse 0:39935bb3c1a1 66 #define I2C_SLV1_ADDR 0x28
onehorse 0:39935bb3c1a1 67 #define I2C_SLV1_REG 0x29
onehorse 0:39935bb3c1a1 68 #define I2C_SLV1_CTRL 0x2A
onehorse 0:39935bb3c1a1 69 #define I2C_SLV2_ADDR 0x2B
onehorse 0:39935bb3c1a1 70 #define I2C_SLV2_REG 0x2C
onehorse 0:39935bb3c1a1 71 #define I2C_SLV2_CTRL 0x2D
onehorse 0:39935bb3c1a1 72 #define I2C_SLV3_ADDR 0x2E
onehorse 0:39935bb3c1a1 73 #define I2C_SLV3_REG 0x2F
onehorse 0:39935bb3c1a1 74 #define I2C_SLV3_CTRL 0x30
onehorse 0:39935bb3c1a1 75 #define I2C_SLV4_ADDR 0x31
onehorse 0:39935bb3c1a1 76 #define I2C_SLV4_REG 0x32
onehorse 0:39935bb3c1a1 77 #define I2C_SLV4_DO 0x33
onehorse 0:39935bb3c1a1 78 #define I2C_SLV4_CTRL 0x34
onehorse 0:39935bb3c1a1 79 #define I2C_SLV4_DI 0x35
onehorse 0:39935bb3c1a1 80 #define I2C_MST_STATUS 0x36
onehorse 0:39935bb3c1a1 81 #define INT_PIN_CFG 0x37
onehorse 0:39935bb3c1a1 82 #define INT_ENABLE 0x38
onehorse 0:39935bb3c1a1 83 #define DMP_INT_STATUS 0x39 // Check DMP interrupt
onehorse 0:39935bb3c1a1 84 #define INT_STATUS 0x3A
onehorse 0:39935bb3c1a1 85 #define ACCEL_XOUT_H 0x3B
onehorse 0:39935bb3c1a1 86 #define ACCEL_XOUT_L 0x3C
onehorse 0:39935bb3c1a1 87 #define ACCEL_YOUT_H 0x3D
onehorse 0:39935bb3c1a1 88 #define ACCEL_YOUT_L 0x3E
onehorse 0:39935bb3c1a1 89 #define ACCEL_ZOUT_H 0x3F
onehorse 0:39935bb3c1a1 90 #define ACCEL_ZOUT_L 0x40
onehorse 0:39935bb3c1a1 91 #define TEMP_OUT_H 0x41
onehorse 0:39935bb3c1a1 92 #define TEMP_OUT_L 0x42
onehorse 0:39935bb3c1a1 93 #define GYRO_XOUT_H 0x43
onehorse 0:39935bb3c1a1 94 #define GYRO_XOUT_L 0x44
onehorse 0:39935bb3c1a1 95 #define GYRO_YOUT_H 0x45
onehorse 0:39935bb3c1a1 96 #define GYRO_YOUT_L 0x46
onehorse 0:39935bb3c1a1 97 #define GYRO_ZOUT_H 0x47
onehorse 0:39935bb3c1a1 98 #define GYRO_ZOUT_L 0x48
onehorse 0:39935bb3c1a1 99 #define EXT_SENS_DATA_00 0x49
onehorse 0:39935bb3c1a1 100 #define EXT_SENS_DATA_01 0x4A
onehorse 0:39935bb3c1a1 101 #define EXT_SENS_DATA_02 0x4B
onehorse 0:39935bb3c1a1 102 #define EXT_SENS_DATA_03 0x4C
onehorse 0:39935bb3c1a1 103 #define EXT_SENS_DATA_04 0x4D
onehorse 0:39935bb3c1a1 104 #define EXT_SENS_DATA_05 0x4E
onehorse 0:39935bb3c1a1 105 #define EXT_SENS_DATA_06 0x4F
onehorse 0:39935bb3c1a1 106 #define EXT_SENS_DATA_07 0x50
onehorse 0:39935bb3c1a1 107 #define EXT_SENS_DATA_08 0x51
onehorse 0:39935bb3c1a1 108 #define EXT_SENS_DATA_09 0x52
onehorse 0:39935bb3c1a1 109 #define EXT_SENS_DATA_10 0x53
onehorse 0:39935bb3c1a1 110 #define EXT_SENS_DATA_11 0x54
onehorse 0:39935bb3c1a1 111 #define EXT_SENS_DATA_12 0x55
onehorse 0:39935bb3c1a1 112 #define EXT_SENS_DATA_13 0x56
onehorse 0:39935bb3c1a1 113 #define EXT_SENS_DATA_14 0x57
onehorse 0:39935bb3c1a1 114 #define EXT_SENS_DATA_15 0x58
onehorse 0:39935bb3c1a1 115 #define EXT_SENS_DATA_16 0x59
onehorse 0:39935bb3c1a1 116 #define EXT_SENS_DATA_17 0x5A
onehorse 0:39935bb3c1a1 117 #define EXT_SENS_DATA_18 0x5B
onehorse 0:39935bb3c1a1 118 #define EXT_SENS_DATA_19 0x5C
onehorse 0:39935bb3c1a1 119 #define EXT_SENS_DATA_20 0x5D
onehorse 0:39935bb3c1a1 120 #define EXT_SENS_DATA_21 0x5E
onehorse 0:39935bb3c1a1 121 #define EXT_SENS_DATA_22 0x5F
onehorse 0:39935bb3c1a1 122 #define EXT_SENS_DATA_23 0x60
onehorse 0:39935bb3c1a1 123 #define MOT_DETECT_STATUS 0x61
onehorse 0:39935bb3c1a1 124 #define I2C_SLV0_DO 0x63
onehorse 0:39935bb3c1a1 125 #define I2C_SLV1_DO 0x64
onehorse 0:39935bb3c1a1 126 #define I2C_SLV2_DO 0x65
onehorse 0:39935bb3c1a1 127 #define I2C_SLV3_DO 0x66
onehorse 0:39935bb3c1a1 128 #define I2C_MST_DELAY_CTRL 0x67
onehorse 0:39935bb3c1a1 129 #define SIGNAL_PATH_RESET 0x68
onehorse 0:39935bb3c1a1 130 #define MOT_DETECT_CTRL 0x69
onehorse 0:39935bb3c1a1 131 #define USER_CTRL 0x6A // Bit 7 enable DMP, bit 3 reset DMP
onehorse 0:39935bb3c1a1 132 #define PWR_MGMT_1 0x6B // Device defaults to the SLEEP mode
onehorse 0:39935bb3c1a1 133 #define PWR_MGMT_2 0x6C
onehorse 0:39935bb3c1a1 134 #define DMP_BANK 0x6D // Activates a specific bank in the DMP
onehorse 0:39935bb3c1a1 135 #define DMP_RW_PNT 0x6E // Set read/write pointer to a specific start address in specified DMP bank
onehorse 0:39935bb3c1a1 136 #define DMP_REG 0x6F // Register in DMP from which to read or to which to write
onehorse 0:39935bb3c1a1 137 #define DMP_REG_1 0x70
onehorse 0:39935bb3c1a1 138 #define DMP_REG_2 0x71
onehorse 0:39935bb3c1a1 139 #define FIFO_COUNTH 0x72
onehorse 0:39935bb3c1a1 140 #define FIFO_COUNTL 0x73
onehorse 0:39935bb3c1a1 141 #define FIFO_R_W 0x74
onehorse 0:39935bb3c1a1 142 #define WHO_AM_I_MPU9150 0x75 // Should return 0x68
onehorse 0:39935bb3c1a1 143
onehorse 0:39935bb3c1a1 144
onehorse 0:39935bb3c1a1 145 // Using the GY-9150 breakout board, ADO is set to 0
onehorse 0:39935bb3c1a1 146 // Seven-bit device address is 110100 for ADO = 0 and 110101 for ADO = 1
onehorse 0:39935bb3c1a1 147 // mbed uses the eight-bit device address, so shift seven-bit addresses left by one!
onehorse 0:39935bb3c1a1 148 #define ADO 0
onehorse 0:39935bb3c1a1 149 #if ADO
onehorse 0:39935bb3c1a1 150 #define MPU9150_ADDRESS 0x69<<1 // Device address when ADO = 1
onehorse 0:39935bb3c1a1 151 #else
onehorse 0:39935bb3c1a1 152 #define MPU9150_ADDRESS 0x68<<1 // Device address when ADO = 0
onehorse 0:39935bb3c1a1 153 #endif
onehorse 0:39935bb3c1a1 154
onehorse 0:39935bb3c1a1 155 // Set initial input parameters
onehorse 0:39935bb3c1a1 156 enum Ascale {
onehorse 0:39935bb3c1a1 157 AFS_2G = 0,
onehorse 0:39935bb3c1a1 158 AFS_4G,
onehorse 0:39935bb3c1a1 159 AFS_8G,
onehorse 0:39935bb3c1a1 160 AFS_16G
onehorse 0:39935bb3c1a1 161 };
onehorse 0:39935bb3c1a1 162
onehorse 0:39935bb3c1a1 163 enum Gscale {
onehorse 0:39935bb3c1a1 164 GFS_250DPS = 0,
onehorse 0:39935bb3c1a1 165 GFS_500DPS,
onehorse 0:39935bb3c1a1 166 GFS_1000DPS,
onehorse 0:39935bb3c1a1 167 GFS_2000DPS
onehorse 0:39935bb3c1a1 168 };
onehorse 0:39935bb3c1a1 169
onehorse 0:39935bb3c1a1 170 uint8_t Ascale = AFS_2G; // AFS_2G, AFS_4G, AFS_8G, AFS_16G
onehorse 0:39935bb3c1a1 171 uint8_t Gscale = GFS_250DPS; // GFS_250DPS, GFS_500DPS, GFS_1000DPS, GFS_2000DPS
onehorse 0:39935bb3c1a1 172 float aRes, gRes, mRes; // scale resolutions per LSB for the sensors
onehorse 0:39935bb3c1a1 173
onehorse 0:39935bb3c1a1 174 //Set up I2C, (SDA,SCL)
onehorse 0:39935bb3c1a1 175 I2C i2c(I2C_SDA, I2C_SCL);
onehorse 0:39935bb3c1a1 176
onehorse 0:39935bb3c1a1 177 DigitalOut myled(LED1);
onehorse 0:39935bb3c1a1 178
onehorse 0:39935bb3c1a1 179 // Pin definitions
onehorse 0:39935bb3c1a1 180 int intPin = 12; // These can be changed, 2 and 3 are the Arduinos ext int pins
onehorse 0:39935bb3c1a1 181
onehorse 0:39935bb3c1a1 182 int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output
onehorse 0:39935bb3c1a1 183 int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output
onehorse 0:39935bb3c1a1 184 int16_t magCount[3]; // Stores the 16-bit signed magnetometer sensor output
onehorse 0:39935bb3c1a1 185 float magCalibration[3] = {0, 0, 0}, magbias[3] = {0, 0, 0}; // Factory mag calibration and mag bias
onehorse 0:39935bb3c1a1 186 float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}; // Bias corrections for gyro and accelerometer
onehorse 0:39935bb3c1a1 187 float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values
onehorse 0:39935bb3c1a1 188 int16_t tempCount; // Stores the real internal chip temperature in degrees Celsius
onehorse 0:39935bb3c1a1 189 float temperature;
onehorse 0:39935bb3c1a1 190 float SelfTest[6];
onehorse 0:39935bb3c1a1 191
onehorse 0:39935bb3c1a1 192 int delt_t = 0; // used to control display output rate
onehorse 0:39935bb3c1a1 193 int count = 0; // used to control display output rate
onehorse 0:39935bb3c1a1 194
onehorse 0:39935bb3c1a1 195 // parameters for 6 DoF sensor fusion calculations
onehorse 0:39935bb3c1a1 196 float PI = 3.14159265358979323846f;
onehorse 0:39935bb3c1a1 197 float GyroMeasError = PI * (60.0f / 180.0f); // gyroscope measurement error in rads/s (start at 60 deg/s), then reduce after ~10 s to 3
onehorse 0:39935bb3c1a1 198 float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta
onehorse 0:39935bb3c1a1 199 float GyroMeasDrift = PI * (1.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s)
onehorse 0:39935bb3c1a1 200 float zeta = sqrt(3.0f / 4.0f) * GyroMeasDrift; // compute zeta, the other free parameter in the Madgwick scheme usually set to a small or zero value
onehorse 0:39935bb3c1a1 201 #define Kp 2.0f * 5.0f // these are the free parameters in the Mahony filter and fusion scheme, Kp for proportional feedback, Ki for integral
onehorse 0:39935bb3c1a1 202 #define Ki 0.0f
onehorse 0:39935bb3c1a1 203
onehorse 0:39935bb3c1a1 204 float pitch, yaw, roll;
onehorse 0:39935bb3c1a1 205 float deltat = 0.0f; // integration interval for both filter schemes
onehorse 0:39935bb3c1a1 206 int lastUpdate = 0, firstUpdate = 0, Now = 0; // used to calculate integration interval // used to calculate integration interval
onehorse 0:39935bb3c1a1 207 float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion
onehorse 0:39935bb3c1a1 208 float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method
onehorse 0:39935bb3c1a1 209
onehorse 0:39935bb3c1a1 210 class MPU9150 {
onehorse 0:39935bb3c1a1 211
onehorse 0:39935bb3c1a1 212 protected:
onehorse 0:39935bb3c1a1 213
onehorse 0:39935bb3c1a1 214 public:
onehorse 0:39935bb3c1a1 215 //===================================================================================================================
onehorse 0:39935bb3c1a1 216 //====== Set of useful function to access acceleratio, gyroscope, and temperature data
onehorse 0:39935bb3c1a1 217 //===================================================================================================================
onehorse 0:39935bb3c1a1 218
onehorse 0:39935bb3c1a1 219 void writeByte(uint8_t address, uint8_t subAddress, uint8_t data)
onehorse 0:39935bb3c1a1 220 {
onehorse 0:39935bb3c1a1 221 char data_write[2];
onehorse 0:39935bb3c1a1 222 data_write[0] = subAddress;
onehorse 0:39935bb3c1a1 223 data_write[1] = data;
onehorse 0:39935bb3c1a1 224 i2c.write(address, data_write, 2, 0);
onehorse 0:39935bb3c1a1 225 }
onehorse 0:39935bb3c1a1 226
onehorse 0:39935bb3c1a1 227 char readByte(uint8_t address, uint8_t subAddress)
onehorse 0:39935bb3c1a1 228 {
onehorse 0:39935bb3c1a1 229 char data[1]; // `data` will store the register data
onehorse 0:39935bb3c1a1 230 char data_write[1];
onehorse 0:39935bb3c1a1 231 data_write[0] = subAddress;
onehorse 0:39935bb3c1a1 232 i2c.write(address, data_write, 1, 1); // no stop
onehorse 0:39935bb3c1a1 233 i2c.read(address, data, 1, 0);
onehorse 0:39935bb3c1a1 234 return data[0];
onehorse 0:39935bb3c1a1 235 }
onehorse 0:39935bb3c1a1 236
onehorse 0:39935bb3c1a1 237 void readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest)
onehorse 0:39935bb3c1a1 238 {
onehorse 0:39935bb3c1a1 239 char data[14];
onehorse 0:39935bb3c1a1 240 char data_write[1];
onehorse 0:39935bb3c1a1 241 data_write[0] = subAddress;
onehorse 0:39935bb3c1a1 242 i2c.write(address, data_write, 1, 1); // no stop
onehorse 0:39935bb3c1a1 243 i2c.read(address, data, count, 0);
onehorse 0:39935bb3c1a1 244 for(int ii = 0; ii < count; ii++) {
onehorse 0:39935bb3c1a1 245 dest[ii] = data[ii];
onehorse 0:39935bb3c1a1 246 }
onehorse 0:39935bb3c1a1 247 }
onehorse 0:39935bb3c1a1 248
onehorse 0:39935bb3c1a1 249
onehorse 0:39935bb3c1a1 250 void getGres() {
onehorse 0:39935bb3c1a1 251 switch (Gscale)
onehorse 0:39935bb3c1a1 252 {
onehorse 0:39935bb3c1a1 253 // Possible gyro scales (and their register bit settings) are:
onehorse 0:39935bb3c1a1 254 // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS (11).
onehorse 0:39935bb3c1a1 255 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value:
onehorse 0:39935bb3c1a1 256 case GFS_250DPS:
onehorse 0:39935bb3c1a1 257 gRes = 250.0/32768.0;
onehorse 0:39935bb3c1a1 258 break;
onehorse 0:39935bb3c1a1 259 case GFS_500DPS:
onehorse 0:39935bb3c1a1 260 gRes = 500.0/32768.0;
onehorse 0:39935bb3c1a1 261 break;
onehorse 0:39935bb3c1a1 262 case GFS_1000DPS:
onehorse 0:39935bb3c1a1 263 gRes = 1000.0/32768.0;
onehorse 0:39935bb3c1a1 264 break;
onehorse 0:39935bb3c1a1 265 case GFS_2000DPS:
onehorse 0:39935bb3c1a1 266 gRes = 2000.0/32768.0;
onehorse 0:39935bb3c1a1 267 break;
onehorse 0:39935bb3c1a1 268 }
onehorse 0:39935bb3c1a1 269 }
onehorse 0:39935bb3c1a1 270
onehorse 0:39935bb3c1a1 271
onehorse 0:39935bb3c1a1 272 void getAres() {
onehorse 0:39935bb3c1a1 273 switch (Ascale)
onehorse 0:39935bb3c1a1 274 {
onehorse 0:39935bb3c1a1 275 // Possible accelerometer scales (and their register bit settings) are:
onehorse 0:39935bb3c1a1 276 // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs (11).
onehorse 0:39935bb3c1a1 277 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value:
onehorse 0:39935bb3c1a1 278 case AFS_2G:
onehorse 0:39935bb3c1a1 279 aRes = 2.0/32768.0;
onehorse 0:39935bb3c1a1 280 break;
onehorse 0:39935bb3c1a1 281 case AFS_4G:
onehorse 0:39935bb3c1a1 282 aRes = 4.0/32768.0;
onehorse 0:39935bb3c1a1 283 break;
onehorse 0:39935bb3c1a1 284 case AFS_8G:
onehorse 0:39935bb3c1a1 285 aRes = 8.0/32768.0;
onehorse 0:39935bb3c1a1 286 break;
onehorse 0:39935bb3c1a1 287 case AFS_16G:
onehorse 0:39935bb3c1a1 288 aRes = 16.0/32768.0;
onehorse 0:39935bb3c1a1 289 break;
onehorse 0:39935bb3c1a1 290 }
onehorse 0:39935bb3c1a1 291 }
onehorse 0:39935bb3c1a1 292
onehorse 0:39935bb3c1a1 293
onehorse 0:39935bb3c1a1 294 void readAccelData(int16_t * destination)
onehorse 0:39935bb3c1a1 295 {
onehorse 0:39935bb3c1a1 296 uint8_t rawData[6]; // x/y/z accel register data stored here
onehorse 0:39935bb3c1a1 297 readBytes(MPU9150_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array
onehorse 0:39935bb3c1a1 298 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
onehorse 0:39935bb3c1a1 299 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
onehorse 0:39935bb3c1a1 300 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
onehorse 0:39935bb3c1a1 301 }
onehorse 0:39935bb3c1a1 302
onehorse 0:39935bb3c1a1 303 void readGyroData(int16_t * destination)
onehorse 0:39935bb3c1a1 304 {
onehorse 0:39935bb3c1a1 305 uint8_t rawData[6]; // x/y/z gyro register data stored here
onehorse 0:39935bb3c1a1 306 readBytes(MPU9150_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
onehorse 0:39935bb3c1a1 307 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
onehorse 0:39935bb3c1a1 308 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
onehorse 0:39935bb3c1a1 309 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
onehorse 0:39935bb3c1a1 310 }
onehorse 0:39935bb3c1a1 311
onehorse 0:39935bb3c1a1 312 void readMagData(int16_t * destination)
onehorse 0:39935bb3c1a1 313 {
onehorse 0:39935bb3c1a1 314 uint8_t rawData[6]; // x/y/z gyro register data stored here
onehorse 0:39935bb3c1a1 315 writeByte(AK8975A_ADDRESS, AK8975A_CNTL, 0x01); // toggle enable data read from magnetometer, no continuous read mode!
onehorse 0:39935bb3c1a1 316 wait(0.01);
onehorse 0:39935bb3c1a1 317 // Only accept a new magnetometer data read if the data ready bit is set and
onehorse 0:39935bb3c1a1 318 // if there are no sensor overflow or data read errors
onehorse 0:39935bb3c1a1 319 if(readByte(AK8975A_ADDRESS, AK8975A_ST1) & 0x01) { // wait for magnetometer data ready bit to be set
onehorse 0:39935bb3c1a1 320 readBytes(AK8975A_ADDRESS, AK8975A_XOUT_L, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
onehorse 0:39935bb3c1a1 321 destination[0] = ((int16_t)rawData[1] << 8) | rawData[0] ; // Turn the MSB and LSB into a signed 16-bit value
onehorse 0:39935bb3c1a1 322 destination[1] = ((int16_t)rawData[3] << 8) | rawData[2] ;
onehorse 0:39935bb3c1a1 323 destination[2] = ((int16_t)rawData[5] << 8) | rawData[4] ;
onehorse 0:39935bb3c1a1 324 }
onehorse 0:39935bb3c1a1 325 }
onehorse 0:39935bb3c1a1 326
onehorse 0:39935bb3c1a1 327 void initAK8975A(float * destination)
onehorse 0:39935bb3c1a1 328 {
onehorse 0:39935bb3c1a1 329 uint8_t rawData[3]; // x/y/z gyro register data stored here
onehorse 0:39935bb3c1a1 330 writeByte(AK8975A_ADDRESS, AK8975A_CNTL, 0x00); // Power down
onehorse 0:39935bb3c1a1 331 wait(0.01);
onehorse 0:39935bb3c1a1 332 writeByte(AK8975A_ADDRESS, AK8975A_CNTL, 0x0F); // Enter Fuse ROM access mode
onehorse 0:39935bb3c1a1 333 wait(0.01);
onehorse 0:39935bb3c1a1 334 readBytes(AK8975A_ADDRESS, AK8975A_ASAX, 3, &rawData[0]); // Read the x-, y-, and z-axis calibration values
onehorse 0:39935bb3c1a1 335 destination[0] = (float)(rawData[0] - 128)/256.0f + 1.0f; // Return x-axis sensitivity adjustment values
onehorse 0:39935bb3c1a1 336 destination[1] = (float)(rawData[1] - 128)/256.0f + 1.0f;
onehorse 0:39935bb3c1a1 337 destination[2] = (float)(rawData[2] - 128)/256.0f + 1.0f;
onehorse 0:39935bb3c1a1 338 }
onehorse 0:39935bb3c1a1 339
onehorse 0:39935bb3c1a1 340 int16_t readTempData()
onehorse 0:39935bb3c1a1 341 {
onehorse 0:39935bb3c1a1 342 uint8_t rawData[2]; // x/y/z gyro register data stored here
onehorse 0:39935bb3c1a1 343 readBytes(MPU9150_ADDRESS, TEMP_OUT_H, 2, &rawData[0]); // Read the two raw data registers sequentially into data array
onehorse 0:39935bb3c1a1 344 return ((int16_t)rawData[0] << 8) | rawData[1] ; // Turn the MSB and LSB into a 16-bit value
onehorse 0:39935bb3c1a1 345 }
onehorse 0:39935bb3c1a1 346
onehorse 0:39935bb3c1a1 347 void resetMPU9150() {
onehorse 0:39935bb3c1a1 348 // reset device
onehorse 0:39935bb3c1a1 349 writeByte(MPU9150_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
onehorse 0:39935bb3c1a1 350 wait(0.1);
onehorse 0:39935bb3c1a1 351 }
onehorse 0:39935bb3c1a1 352
onehorse 0:39935bb3c1a1 353
onehorse 0:39935bb3c1a1 354
onehorse 0:39935bb3c1a1 355 void initMPU9150()
onehorse 0:39935bb3c1a1 356 {
onehorse 0:39935bb3c1a1 357 // Initialize MPU9150 device
onehorse 0:39935bb3c1a1 358 // wake up device
onehorse 0:39935bb3c1a1 359 writeByte(MPU9150_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors
onehorse 0:39935bb3c1a1 360 wait(0.1); // Delay 100 ms for PLL to get established on x-axis gyro; should check for PLL ready interrupt
onehorse 0:39935bb3c1a1 361
onehorse 0:39935bb3c1a1 362 // get stable time source
onehorse 0:39935bb3c1a1 363 writeByte(MPU9150_ADDRESS, PWR_MGMT_1, 0x01); // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001
onehorse 0:39935bb3c1a1 364
onehorse 0:39935bb3c1a1 365 // Configure Gyro and Accelerometer
onehorse 0:39935bb3c1a1 366 // Disable FSYNC and set accelerometer and gyro bandwidth to 44 and 42 Hz, respectively;
onehorse 0:39935bb3c1a1 367 // DLPF_CFG = bits 2:0 = 010; this sets the sample rate at 1 kHz for both
onehorse 0:39935bb3c1a1 368 // Maximum delay is 4.9 ms which is just over a 200 Hz maximum rate
onehorse 0:39935bb3c1a1 369 writeByte(MPU9150_ADDRESS, CONFIG, 0x03);
onehorse 0:39935bb3c1a1 370
onehorse 0:39935bb3c1a1 371 // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV)
onehorse 0:39935bb3c1a1 372 writeByte(MPU9150_ADDRESS, SMPLRT_DIV, 0x04); // Use a 200 Hz rate; the same rate set in CONFIG above
onehorse 0:39935bb3c1a1 373
onehorse 0:39935bb3c1a1 374 // Set gyroscope full scale range
onehorse 0:39935bb3c1a1 375 // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3
onehorse 0:39935bb3c1a1 376 uint8_t c = readByte(MPU9150_ADDRESS, GYRO_CONFIG);
onehorse 0:39935bb3c1a1 377 writeByte(MPU9150_ADDRESS, GYRO_CONFIG, c & ~0xE0); // Clear self-test bits [7:5]
onehorse 0:39935bb3c1a1 378 writeByte(MPU9150_ADDRESS, GYRO_CONFIG, c & ~0x18); // Clear AFS bits [4:3]
onehorse 0:39935bb3c1a1 379 writeByte(MPU9150_ADDRESS, GYRO_CONFIG, c | Gscale << 3); // Set full scale range for the gyro
onehorse 0:39935bb3c1a1 380
onehorse 0:39935bb3c1a1 381 // Set accelerometer configuration
onehorse 0:39935bb3c1a1 382 c = readByte(MPU9150_ADDRESS, ACCEL_CONFIG);
onehorse 0:39935bb3c1a1 383 writeByte(MPU9150_ADDRESS, ACCEL_CONFIG, c & ~0xE0); // Clear self-test bits [7:5]
onehorse 0:39935bb3c1a1 384 writeByte(MPU9150_ADDRESS, ACCEL_CONFIG, c & ~0x18); // Clear AFS bits [4:3]
onehorse 0:39935bb3c1a1 385 writeByte(MPU9150_ADDRESS, ACCEL_CONFIG, c | Ascale << 3); // Set full scale range for the accelerometer
onehorse 0:39935bb3c1a1 386
onehorse 0:39935bb3c1a1 387 // The accelerometer, gyro, and thermometer are set to 1 kHz sample rates,
onehorse 0:39935bb3c1a1 388 // but all these rates are further reduced by a factor of 5 to 200 Hz because of the SMPLRT_DIV setting
onehorse 0:39935bb3c1a1 389
onehorse 0:39935bb3c1a1 390 // Configure Interrupts and Bypass Enable
onehorse 0:39935bb3c1a1 391 // Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips
onehorse 0:39935bb3c1a1 392 // can join the I2C bus and all can be controlled by the Arduino as master
onehorse 0:39935bb3c1a1 393 writeByte(MPU9150_ADDRESS, INT_PIN_CFG, 0x22);
onehorse 0:39935bb3c1a1 394 writeByte(MPU9150_ADDRESS, INT_ENABLE, 0x01); // Enable data ready (bit 0) interrupt
onehorse 0:39935bb3c1a1 395 }
onehorse 0:39935bb3c1a1 396
onehorse 0:39935bb3c1a1 397 // Function which accumulates gyro and accelerometer data after device initialization. It calculates the average
onehorse 0:39935bb3c1a1 398 // of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers.
onehorse 0:39935bb3c1a1 399 void calibrateMPU9150(float * dest1, float * dest2)
onehorse 0:39935bb3c1a1 400 {
onehorse 0:39935bb3c1a1 401 uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data
onehorse 0:39935bb3c1a1 402 uint16_t ii, packet_count, fifo_count;
onehorse 0:39935bb3c1a1 403 int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0};
onehorse 0:39935bb3c1a1 404
onehorse 0:39935bb3c1a1 405 // reset device, reset all registers, clear gyro and accelerometer bias registers
onehorse 0:39935bb3c1a1 406 writeByte(MPU9150_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
onehorse 0:39935bb3c1a1 407 wait(0.1);
onehorse 0:39935bb3c1a1 408
onehorse 0:39935bb3c1a1 409 // get stable time source
onehorse 0:39935bb3c1a1 410 // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001
onehorse 0:39935bb3c1a1 411 writeByte(MPU9150_ADDRESS, PWR_MGMT_1, 0x01);
onehorse 0:39935bb3c1a1 412 writeByte(MPU9150_ADDRESS, PWR_MGMT_2, 0x00);
onehorse 0:39935bb3c1a1 413 wait(0.2);
onehorse 0:39935bb3c1a1 414
onehorse 0:39935bb3c1a1 415 // Configure device for bias calculation
onehorse 0:39935bb3c1a1 416 writeByte(MPU9150_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts
onehorse 0:39935bb3c1a1 417 writeByte(MPU9150_ADDRESS, FIFO_EN, 0x00); // Disable FIFO
onehorse 0:39935bb3c1a1 418 writeByte(MPU9150_ADDRESS, PWR_MGMT_1, 0x00); // Turn on internal clock source
onehorse 0:39935bb3c1a1 419 writeByte(MPU9150_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master
onehorse 0:39935bb3c1a1 420 writeByte(MPU9150_ADDRESS, USER_CTRL, 0x00); // Disable FIFO and I2C master modes
onehorse 0:39935bb3c1a1 421 writeByte(MPU9150_ADDRESS, USER_CTRL, 0x0C); // Reset FIFO and DMP
onehorse 0:39935bb3c1a1 422 wait(0.015);
onehorse 0:39935bb3c1a1 423
onehorse 0:39935bb3c1a1 424 // Configure MPU9150 gyro and accelerometer for bias calculation
onehorse 0:39935bb3c1a1 425 writeByte(MPU9150_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz
onehorse 0:39935bb3c1a1 426 writeByte(MPU9150_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz
onehorse 0:39935bb3c1a1 427 writeByte(MPU9150_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to 250 degrees per second, maximum sensitivity
onehorse 0:39935bb3c1a1 428 writeByte(MPU9150_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity
onehorse 0:39935bb3c1a1 429
onehorse 0:39935bb3c1a1 430 uint16_t gyrosensitivity = 131; // = 131 LSB/degrees/sec
onehorse 0:39935bb3c1a1 431 uint16_t accelsensitivity = 16384; // = 16384 LSB/g
onehorse 0:39935bb3c1a1 432
onehorse 0:39935bb3c1a1 433 // Configure FIFO to capture accelerometer and gyro data for bias calculation
onehorse 0:39935bb3c1a1 434 writeByte(MPU9150_ADDRESS, USER_CTRL, 0x40); // Enable FIFO
onehorse 0:39935bb3c1a1 435 writeByte(MPU9150_ADDRESS, FIFO_EN, 0x78); // Enable gyro and accelerometer sensors for FIFO (max size 1024 bytes in MPU9150)
onehorse 0:39935bb3c1a1 436 wait(0.08); // accumulate 80 samples in 80 milliseconds = 960 bytes
onehorse 0:39935bb3c1a1 437
onehorse 0:39935bb3c1a1 438 // At end of sample accumulation, turn off FIFO sensor read
onehorse 0:39935bb3c1a1 439 writeByte(MPU9150_ADDRESS, FIFO_EN, 0x00); // Disable gyro and accelerometer sensors for FIFO
onehorse 0:39935bb3c1a1 440 readBytes(MPU9150_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count
onehorse 0:39935bb3c1a1 441 fifo_count = ((uint16_t)data[0] << 8) | data[1];
onehorse 0:39935bb3c1a1 442 packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging
onehorse 0:39935bb3c1a1 443
onehorse 0:39935bb3c1a1 444 for (ii = 0; ii < packet_count; ii++) {
onehorse 0:39935bb3c1a1 445 int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0};
onehorse 0:39935bb3c1a1 446 readBytes(MPU9150_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging
onehorse 0:39935bb3c1a1 447 accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1] ) ; // Form signed 16-bit integer for each sample in FIFO
onehorse 0:39935bb3c1a1 448 accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3] ) ;
onehorse 0:39935bb3c1a1 449 accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5] ) ;
onehorse 0:39935bb3c1a1 450 gyro_temp[0] = (int16_t) (((int16_t)data[6] << 8) | data[7] ) ;
onehorse 0:39935bb3c1a1 451 gyro_temp[1] = (int16_t) (((int16_t)data[8] << 8) | data[9] ) ;
onehorse 0:39935bb3c1a1 452 gyro_temp[2] = (int16_t) (((int16_t)data[10] << 8) | data[11]) ;
onehorse 0:39935bb3c1a1 453
onehorse 0:39935bb3c1a1 454 accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases
onehorse 0:39935bb3c1a1 455 accel_bias[1] += (int32_t) accel_temp[1];
onehorse 0:39935bb3c1a1 456 accel_bias[2] += (int32_t) accel_temp[2];
onehorse 0:39935bb3c1a1 457 gyro_bias[0] += (int32_t) gyro_temp[0];
onehorse 0:39935bb3c1a1 458 gyro_bias[1] += (int32_t) gyro_temp[1];
onehorse 0:39935bb3c1a1 459 gyro_bias[2] += (int32_t) gyro_temp[2];
onehorse 0:39935bb3c1a1 460
onehorse 0:39935bb3c1a1 461 }
onehorse 0:39935bb3c1a1 462 accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases
onehorse 0:39935bb3c1a1 463 accel_bias[1] /= (int32_t) packet_count;
onehorse 0:39935bb3c1a1 464 accel_bias[2] /= (int32_t) packet_count;
onehorse 0:39935bb3c1a1 465 gyro_bias[0] /= (int32_t) packet_count;
onehorse 0:39935bb3c1a1 466 gyro_bias[1] /= (int32_t) packet_count;
onehorse 0:39935bb3c1a1 467 gyro_bias[2] /= (int32_t) packet_count;
onehorse 0:39935bb3c1a1 468
onehorse 0:39935bb3c1a1 469 if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) accelsensitivity;} // Remove gravity from the z-axis accelerometer bias calculation
onehorse 0:39935bb3c1a1 470 else {accel_bias[2] += (int32_t) accelsensitivity;}
onehorse 0:39935bb3c1a1 471
onehorse 0:39935bb3c1a1 472 // Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup
onehorse 0:39935bb3c1a1 473 data[0] = (-gyro_bias[0]/4 >> 8) & 0xFF; // Divide by 4 to get 32.9 LSB per deg/s to conform to expected bias input format
onehorse 0:39935bb3c1a1 474 data[1] = (-gyro_bias[0]/4) & 0xFF; // Biases are additive, so change sign on calculated average gyro biases
onehorse 0:39935bb3c1a1 475 data[2] = (-gyro_bias[1]/4 >> 8) & 0xFF;
onehorse 0:39935bb3c1a1 476 data[3] = (-gyro_bias[1]/4) & 0xFF;
onehorse 0:39935bb3c1a1 477 data[4] = (-gyro_bias[2]/4 >> 8) & 0xFF;
onehorse 0:39935bb3c1a1 478 data[5] = (-gyro_bias[2]/4) & 0xFF;
onehorse 0:39935bb3c1a1 479
onehorse 0:39935bb3c1a1 480 /// Push gyro biases to hardware registers
onehorse 0:39935bb3c1a1 481 writeByte(MPU9150_ADDRESS, XG_OFFS_USRH, data[0]);
onehorse 0:39935bb3c1a1 482 writeByte(MPU9150_ADDRESS, XG_OFFS_USRL, data[1]);
onehorse 0:39935bb3c1a1 483 writeByte(MPU9150_ADDRESS, YG_OFFS_USRH, data[2]);
onehorse 0:39935bb3c1a1 484 writeByte(MPU9150_ADDRESS, YG_OFFS_USRL, data[3]);
onehorse 0:39935bb3c1a1 485 writeByte(MPU9150_ADDRESS, ZG_OFFS_USRH, data[4]);
onehorse 0:39935bb3c1a1 486 writeByte(MPU9150_ADDRESS, ZG_OFFS_USRL, data[5]);
onehorse 0:39935bb3c1a1 487
onehorse 0:39935bb3c1a1 488 dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; // construct gyro bias in deg/s for later manual subtraction
onehorse 0:39935bb3c1a1 489 dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity;
onehorse 0:39935bb3c1a1 490 dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity;
onehorse 0:39935bb3c1a1 491
onehorse 0:39935bb3c1a1 492 // Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain
onehorse 0:39935bb3c1a1 493 // factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold
onehorse 0:39935bb3c1a1 494 // non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature
onehorse 0:39935bb3c1a1 495 // compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that
onehorse 0:39935bb3c1a1 496 // the accelerometer biases calculated above must be divided by 8.
onehorse 0:39935bb3c1a1 497
onehorse 0:39935bb3c1a1 498 int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases
onehorse 0:39935bb3c1a1 499 readBytes(MPU9150_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values
onehorse 0:39935bb3c1a1 500 accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1];
onehorse 0:39935bb3c1a1 501 readBytes(MPU9150_ADDRESS, YA_OFFSET_H, 2, &data[0]);
onehorse 0:39935bb3c1a1 502 accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1];
onehorse 0:39935bb3c1a1 503 readBytes(MPU9150_ADDRESS, ZA_OFFSET_H, 2, &data[0]);
onehorse 0:39935bb3c1a1 504 accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1];
onehorse 0:39935bb3c1a1 505
onehorse 0:39935bb3c1a1 506 uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers
onehorse 0:39935bb3c1a1 507 uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis
onehorse 0:39935bb3c1a1 508
onehorse 0:39935bb3c1a1 509 for(ii = 0; ii < 3; ii++) {
onehorse 0:39935bb3c1a1 510 if(accel_bias_reg[ii] & mask) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit
onehorse 0:39935bb3c1a1 511 }
onehorse 0:39935bb3c1a1 512
onehorse 0:39935bb3c1a1 513 // Construct total accelerometer bias, including calculated average accelerometer bias from above
onehorse 0:39935bb3c1a1 514 accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale)
onehorse 0:39935bb3c1a1 515 accel_bias_reg[1] -= (accel_bias[1]/8);
onehorse 0:39935bb3c1a1 516 accel_bias_reg[2] -= (accel_bias[2]/8);
onehorse 0:39935bb3c1a1 517
onehorse 0:39935bb3c1a1 518 data[0] = (accel_bias_reg[0] >> 8) & 0xFF;
onehorse 0:39935bb3c1a1 519 data[1] = (accel_bias_reg[0]) & 0xFF;
onehorse 0:39935bb3c1a1 520 data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers
onehorse 0:39935bb3c1a1 521 data[2] = (accel_bias_reg[1] >> 8) & 0xFF;
onehorse 0:39935bb3c1a1 522 data[3] = (accel_bias_reg[1]) & 0xFF;
onehorse 0:39935bb3c1a1 523 data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers
onehorse 0:39935bb3c1a1 524 data[4] = (accel_bias_reg[2] >> 8) & 0xFF;
onehorse 0:39935bb3c1a1 525 data[5] = (accel_bias_reg[2]) & 0xFF;
onehorse 0:39935bb3c1a1 526 data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers
onehorse 0:39935bb3c1a1 527
onehorse 0:39935bb3c1a1 528 // Apparently this is not working for the acceleration biases in the MPU-9250
onehorse 0:39935bb3c1a1 529 // Are we handling the temperature correction bit properly?
onehorse 0:39935bb3c1a1 530 // Push accelerometer biases to hardware registers
onehorse 0:39935bb3c1a1 531 writeByte(MPU9150_ADDRESS, XA_OFFSET_H, data[0]);
onehorse 0:39935bb3c1a1 532 writeByte(MPU9150_ADDRESS, XA_OFFSET_L_TC, data[1]);
onehorse 0:39935bb3c1a1 533 writeByte(MPU9150_ADDRESS, YA_OFFSET_H, data[2]);
onehorse 0:39935bb3c1a1 534 writeByte(MPU9150_ADDRESS, YA_OFFSET_L_TC, data[3]);
onehorse 0:39935bb3c1a1 535 writeByte(MPU9150_ADDRESS, ZA_OFFSET_H, data[4]);
onehorse 0:39935bb3c1a1 536 writeByte(MPU9150_ADDRESS, ZA_OFFSET_L_TC, data[5]);
onehorse 0:39935bb3c1a1 537
onehorse 0:39935bb3c1a1 538 // Output scaled accelerometer biases for manual subtraction in the main program
onehorse 0:39935bb3c1a1 539 dest2[0] = (float)accel_bias[0]/(float)accelsensitivity;
onehorse 0:39935bb3c1a1 540 dest2[1] = (float)accel_bias[1]/(float)accelsensitivity;
onehorse 0:39935bb3c1a1 541 dest2[2] = (float)accel_bias[2]/(float)accelsensitivity;
onehorse 0:39935bb3c1a1 542 }
onehorse 0:39935bb3c1a1 543
onehorse 0:39935bb3c1a1 544
onehorse 0:39935bb3c1a1 545 // Accelerometer and gyroscope self test; check calibration wrt factory settings
onehorse 0:39935bb3c1a1 546 void MPU9150SelfTest(float * destination) // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass
onehorse 0:39935bb3c1a1 547 {
onehorse 0:39935bb3c1a1 548 uint8_t rawData[4] = {0, 0, 0, 0};
onehorse 0:39935bb3c1a1 549 uint8_t selfTest[6];
onehorse 0:39935bb3c1a1 550 float factoryTrim[6];
onehorse 0:39935bb3c1a1 551
onehorse 0:39935bb3c1a1 552 // Configure the accelerometer for self-test
onehorse 0:39935bb3c1a1 553 writeByte(MPU9150_ADDRESS, ACCEL_CONFIG, 0xF0); // Enable self test on all three axes and set accelerometer range to +/- 8 g
onehorse 0:39935bb3c1a1 554 writeByte(MPU9150_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s
onehorse 0:39935bb3c1a1 555 wait(0.25); // Delay a while to let the device execute the self-test
onehorse 0:39935bb3c1a1 556 rawData[0] = readByte(MPU9150_ADDRESS, SELF_TEST_X); // X-axis self-test results
onehorse 0:39935bb3c1a1 557 rawData[1] = readByte(MPU9150_ADDRESS, SELF_TEST_Y); // Y-axis self-test results
onehorse 0:39935bb3c1a1 558 rawData[2] = readByte(MPU9150_ADDRESS, SELF_TEST_Z); // Z-axis self-test results
onehorse 0:39935bb3c1a1 559 rawData[3] = readByte(MPU9150_ADDRESS, SELF_TEST_A); // Mixed-axis self-test results
onehorse 0:39935bb3c1a1 560 // Extract the acceleration test results first
onehorse 0:39935bb3c1a1 561 selfTest[0] = (rawData[0] >> 3) | (rawData[3] & 0x30) >> 4 ; // XA_TEST result is a five-bit unsigned integer
onehorse 0:39935bb3c1a1 562 selfTest[1] = (rawData[1] >> 3) | (rawData[3] & 0x0C) >> 4 ; // YA_TEST result is a five-bit unsigned integer
onehorse 0:39935bb3c1a1 563 selfTest[2] = (rawData[2] >> 3) | (rawData[3] & 0x03) >> 4 ; // ZA_TEST result is a five-bit unsigned integer
onehorse 0:39935bb3c1a1 564 // Extract the gyration test results first
onehorse 0:39935bb3c1a1 565 selfTest[3] = rawData[0] & 0x1F ; // XG_TEST result is a five-bit unsigned integer
onehorse 0:39935bb3c1a1 566 selfTest[4] = rawData[1] & 0x1F ; // YG_TEST result is a five-bit unsigned integer
onehorse 0:39935bb3c1a1 567 selfTest[5] = rawData[2] & 0x1F ; // ZG_TEST result is a five-bit unsigned integer
onehorse 0:39935bb3c1a1 568 // Process results to allow final comparison with factory set values
onehorse 0:39935bb3c1a1 569 factoryTrim[0] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[0] - 1.0f)/30.0f))); // FT[Xa] factory trim calculation
onehorse 0:39935bb3c1a1 570 factoryTrim[1] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[1] - 1.0f)/30.0f))); // FT[Ya] factory trim calculation
onehorse 0:39935bb3c1a1 571 factoryTrim[2] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[2] - 1.0f)/30.0f))); // FT[Za] factory trim calculation
onehorse 0:39935bb3c1a1 572 factoryTrim[3] = ( 25.0f*131.0f)*(pow( 1.046f , (selfTest[3] - 1.0f) )); // FT[Xg] factory trim calculation
onehorse 0:39935bb3c1a1 573 factoryTrim[4] = (-25.0f*131.0f)*(pow( 1.046f , (selfTest[4] - 1.0f) )); // FT[Yg] factory trim calculation
onehorse 0:39935bb3c1a1 574 factoryTrim[5] = ( 25.0f*131.0f)*(pow( 1.046f , (selfTest[5] - 1.0f) )); // FT[Zg] factory trim calculation
onehorse 0:39935bb3c1a1 575
onehorse 0:39935bb3c1a1 576 // Output self-test results and factory trim calculation if desired
onehorse 0:39935bb3c1a1 577 // Serial.println(selfTest[0]); Serial.println(selfTest[1]); Serial.println(selfTest[2]);
onehorse 0:39935bb3c1a1 578 // Serial.println(selfTest[3]); Serial.println(selfTest[4]); Serial.println(selfTest[5]);
onehorse 0:39935bb3c1a1 579 // Serial.println(factoryTrim[0]); Serial.println(factoryTrim[1]); Serial.println(factoryTrim[2]);
onehorse 0:39935bb3c1a1 580 // Serial.println(factoryTrim[3]); Serial.println(factoryTrim[4]); Serial.println(factoryTrim[5]);
onehorse 0:39935bb3c1a1 581
onehorse 0:39935bb3c1a1 582 // Report results as a ratio of (STR - FT)/FT; the change from Factory Trim of the Self-Test Response
onehorse 0:39935bb3c1a1 583 // To get to percent, must multiply by 100 and subtract result from 100
onehorse 0:39935bb3c1a1 584 for (int i = 0; i < 6; i++) {
onehorse 0:39935bb3c1a1 585 destination[i] = 100.0f + 100.0f*(selfTest[i] - factoryTrim[i])/factoryTrim[i]; // Report percent differences
onehorse 0:39935bb3c1a1 586 }
onehorse 0:39935bb3c1a1 587
onehorse 0:39935bb3c1a1 588 }
onehorse 0:39935bb3c1a1 589
onehorse 0:39935bb3c1a1 590
onehorse 0:39935bb3c1a1 591
onehorse 0:39935bb3c1a1 592 // Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays"
onehorse 0:39935bb3c1a1 593 // (see http://www.x-io.co.uk/category/open-source/ for examples and more details)
onehorse 0:39935bb3c1a1 594 // which fuses acceleration, rotation rate, and magnetic moments to produce a quaternion-based estimate of absolute
onehorse 0:39935bb3c1a1 595 // device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc.
onehorse 0:39935bb3c1a1 596 // The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms
onehorse 0:39935bb3c1a1 597 // but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz!
onehorse 0:39935bb3c1a1 598 void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz)
onehorse 0:39935bb3c1a1 599 {
onehorse 0:39935bb3c1a1 600 float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability
onehorse 0:39935bb3c1a1 601 float norm;
onehorse 0:39935bb3c1a1 602 float hx, hy, _2bx, _2bz;
onehorse 0:39935bb3c1a1 603 float s1, s2, s3, s4;
onehorse 0:39935bb3c1a1 604 float qDot1, qDot2, qDot3, qDot4;
onehorse 0:39935bb3c1a1 605
onehorse 0:39935bb3c1a1 606 // Auxiliary variables to avoid repeated arithmetic
onehorse 0:39935bb3c1a1 607 float _2q1mx;
onehorse 0:39935bb3c1a1 608 float _2q1my;
onehorse 0:39935bb3c1a1 609 float _2q1mz;
onehorse 0:39935bb3c1a1 610 float _2q2mx;
onehorse 0:39935bb3c1a1 611 float _4bx;
onehorse 0:39935bb3c1a1 612 float _4bz;
onehorse 0:39935bb3c1a1 613 float _2q1 = 2.0f * q1;
onehorse 0:39935bb3c1a1 614 float _2q2 = 2.0f * q2;
onehorse 0:39935bb3c1a1 615 float _2q3 = 2.0f * q3;
onehorse 0:39935bb3c1a1 616 float _2q4 = 2.0f * q4;
onehorse 0:39935bb3c1a1 617 float _2q1q3 = 2.0f * q1 * q3;
onehorse 0:39935bb3c1a1 618 float _2q3q4 = 2.0f * q3 * q4;
onehorse 0:39935bb3c1a1 619 float q1q1 = q1 * q1;
onehorse 0:39935bb3c1a1 620 float q1q2 = q1 * q2;
onehorse 0:39935bb3c1a1 621 float q1q3 = q1 * q3;
onehorse 0:39935bb3c1a1 622 float q1q4 = q1 * q4;
onehorse 0:39935bb3c1a1 623 float q2q2 = q2 * q2;
onehorse 0:39935bb3c1a1 624 float q2q3 = q2 * q3;
onehorse 0:39935bb3c1a1 625 float q2q4 = q2 * q4;
onehorse 0:39935bb3c1a1 626 float q3q3 = q3 * q3;
onehorse 0:39935bb3c1a1 627 float q3q4 = q3 * q4;
onehorse 0:39935bb3c1a1 628 float q4q4 = q4 * q4;
onehorse 0:39935bb3c1a1 629
onehorse 0:39935bb3c1a1 630 // Normalise accelerometer measurement
onehorse 0:39935bb3c1a1 631 norm = sqrt(ax * ax + ay * ay + az * az);
onehorse 0:39935bb3c1a1 632 if (norm == 0.0f) return; // handle NaN
onehorse 0:39935bb3c1a1 633 norm = 1.0f/norm;
onehorse 0:39935bb3c1a1 634 ax *= norm;
onehorse 0:39935bb3c1a1 635 ay *= norm;
onehorse 0:39935bb3c1a1 636 az *= norm;
onehorse 0:39935bb3c1a1 637
onehorse 0:39935bb3c1a1 638 // Normalise magnetometer measurement
onehorse 0:39935bb3c1a1 639 norm = sqrt(mx * mx + my * my + mz * mz);
onehorse 0:39935bb3c1a1 640 if (norm == 0.0f) return; // handle NaN
onehorse 0:39935bb3c1a1 641 norm = 1.0f/norm;
onehorse 0:39935bb3c1a1 642 mx *= norm;
onehorse 0:39935bb3c1a1 643 my *= norm;
onehorse 0:39935bb3c1a1 644 mz *= norm;
onehorse 0:39935bb3c1a1 645
onehorse 0:39935bb3c1a1 646 // Reference direction of Earth's magnetic field
onehorse 0:39935bb3c1a1 647 _2q1mx = 2.0f * q1 * mx;
onehorse 0:39935bb3c1a1 648 _2q1my = 2.0f * q1 * my;
onehorse 0:39935bb3c1a1 649 _2q1mz = 2.0f * q1 * mz;
onehorse 0:39935bb3c1a1 650 _2q2mx = 2.0f * q2 * mx;
onehorse 0:39935bb3c1a1 651 hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4;
onehorse 0:39935bb3c1a1 652 hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4;
onehorse 0:39935bb3c1a1 653 _2bx = sqrt(hx * hx + hy * hy);
onehorse 0:39935bb3c1a1 654 _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4;
onehorse 0:39935bb3c1a1 655 _4bx = 2.0f * _2bx;
onehorse 0:39935bb3c1a1 656 _4bz = 2.0f * _2bz;
onehorse 0:39935bb3c1a1 657
onehorse 0:39935bb3c1a1 658 // Gradient decent algorithm corrective step
onehorse 0:39935bb3c1a1 659 s1 = -_2q3 * (2.0f * q2q4 - _2q1q3 - ax) + _2q2 * (2.0f * q1q2 + _2q3q4 - ay) - _2bz * q3 * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (-_2bx * q4 + _2bz * q2) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + _2bx * q3 * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz);
onehorse 0:39935bb3c1a1 660 s2 = _2q4 * (2.0f * q2q4 - _2q1q3 - ax) + _2q1 * (2.0f * q1q2 + _2q3q4 - ay) - 4.0f * q2 * (1.0f - 2.0f * q2q2 - 2.0f * q3q3 - az) + _2bz * q4 * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (_2bx * q3 + _2bz * q1) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + (_2bx * q4 - _4bz * q2) * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz);
onehorse 0:39935bb3c1a1 661 s3 = -_2q1 * (2.0f * q2q4 - _2q1q3 - ax) + _2q4 * (2.0f * q1q2 + _2q3q4 - ay) - 4.0f * q3 * (1.0f - 2.0f * q2q2 - 2.0f * q3q3 - az) + (-_4bx * q3 - _2bz * q1) * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (_2bx * q2 + _2bz * q4) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + (_2bx * q1 - _4bz * q3) * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz);
onehorse 0:39935bb3c1a1 662 s4 = _2q2 * (2.0f * q2q4 - _2q1q3 - ax) + _2q3 * (2.0f * q1q2 + _2q3q4 - ay) + (-_4bx * q4 + _2bz * q2) * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (-_2bx * q1 + _2bz * q3) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + _2bx * q2 * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz);
onehorse 0:39935bb3c1a1 663 norm = sqrt(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4); // normalise step magnitude
onehorse 0:39935bb3c1a1 664 norm = 1.0f/norm;
onehorse 0:39935bb3c1a1 665 s1 *= norm;
onehorse 0:39935bb3c1a1 666 s2 *= norm;
onehorse 0:39935bb3c1a1 667 s3 *= norm;
onehorse 0:39935bb3c1a1 668 s4 *= norm;
onehorse 0:39935bb3c1a1 669
onehorse 0:39935bb3c1a1 670 // Compute rate of change of quaternion
onehorse 0:39935bb3c1a1 671 qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - beta * s1;
onehorse 0:39935bb3c1a1 672 qDot2 = 0.5f * (q1 * gx + q3 * gz - q4 * gy) - beta * s2;
onehorse 0:39935bb3c1a1 673 qDot3 = 0.5f * (q1 * gy - q2 * gz + q4 * gx) - beta * s3;
onehorse 0:39935bb3c1a1 674 qDot4 = 0.5f * (q1 * gz + q2 * gy - q3 * gx) - beta * s4;
onehorse 0:39935bb3c1a1 675
onehorse 0:39935bb3c1a1 676 // Integrate to yield quaternion
onehorse 0:39935bb3c1a1 677 q1 += qDot1 * deltat;
onehorse 0:39935bb3c1a1 678 q2 += qDot2 * deltat;
onehorse 0:39935bb3c1a1 679 q3 += qDot3 * deltat;
onehorse 0:39935bb3c1a1 680 q4 += qDot4 * deltat;
onehorse 0:39935bb3c1a1 681 norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); // normalise quaternion
onehorse 0:39935bb3c1a1 682 norm = 1.0f/norm;
onehorse 0:39935bb3c1a1 683 q[0] = q1 * norm;
onehorse 0:39935bb3c1a1 684 q[1] = q2 * norm;
onehorse 0:39935bb3c1a1 685 q[2] = q3 * norm;
onehorse 0:39935bb3c1a1 686 q[3] = q4 * norm;
onehorse 0:39935bb3c1a1 687
onehorse 0:39935bb3c1a1 688 }
onehorse 0:39935bb3c1a1 689
onehorse 0:39935bb3c1a1 690
onehorse 0:39935bb3c1a1 691
onehorse 0:39935bb3c1a1 692 // Similar to Madgwick scheme but uses proportional and integral filtering on the error between estimated reference vectors and
onehorse 0:39935bb3c1a1 693 // measured ones.
onehorse 0:39935bb3c1a1 694 void MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz)
onehorse 0:39935bb3c1a1 695 {
onehorse 0:39935bb3c1a1 696 float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability
onehorse 0:39935bb3c1a1 697 float norm;
onehorse 0:39935bb3c1a1 698 float hx, hy, bx, bz;
onehorse 0:39935bb3c1a1 699 float vx, vy, vz, wx, wy, wz;
onehorse 0:39935bb3c1a1 700 float ex, ey, ez;
onehorse 0:39935bb3c1a1 701 float pa, pb, pc;
onehorse 0:39935bb3c1a1 702
onehorse 0:39935bb3c1a1 703 // Auxiliary variables to avoid repeated arithmetic
onehorse 0:39935bb3c1a1 704 float q1q1 = q1 * q1;
onehorse 0:39935bb3c1a1 705 float q1q2 = q1 * q2;
onehorse 0:39935bb3c1a1 706 float q1q3 = q1 * q3;
onehorse 0:39935bb3c1a1 707 float q1q4 = q1 * q4;
onehorse 0:39935bb3c1a1 708 float q2q2 = q2 * q2;
onehorse 0:39935bb3c1a1 709 float q2q3 = q2 * q3;
onehorse 0:39935bb3c1a1 710 float q2q4 = q2 * q4;
onehorse 0:39935bb3c1a1 711 float q3q3 = q3 * q3;
onehorse 0:39935bb3c1a1 712 float q3q4 = q3 * q4;
onehorse 0:39935bb3c1a1 713 float q4q4 = q4 * q4;
onehorse 0:39935bb3c1a1 714
onehorse 0:39935bb3c1a1 715 // Normalise accelerometer measurement
onehorse 0:39935bb3c1a1 716 norm = sqrt(ax * ax + ay * ay + az * az);
onehorse 0:39935bb3c1a1 717 if (norm == 0.0f) return; // handle NaN
onehorse 0:39935bb3c1a1 718 norm = 1.0f / norm; // use reciprocal for division
onehorse 0:39935bb3c1a1 719 ax *= norm;
onehorse 0:39935bb3c1a1 720 ay *= norm;
onehorse 0:39935bb3c1a1 721 az *= norm;
onehorse 0:39935bb3c1a1 722
onehorse 0:39935bb3c1a1 723 // Normalise magnetometer measurement
onehorse 0:39935bb3c1a1 724 norm = sqrt(mx * mx + my * my + mz * mz);
onehorse 0:39935bb3c1a1 725 if (norm == 0.0f) return; // handle NaN
onehorse 0:39935bb3c1a1 726 norm = 1.0f / norm; // use reciprocal for division
onehorse 0:39935bb3c1a1 727 mx *= norm;
onehorse 0:39935bb3c1a1 728 my *= norm;
onehorse 0:39935bb3c1a1 729 mz *= norm;
onehorse 0:39935bb3c1a1 730
onehorse 0:39935bb3c1a1 731 // Reference direction of Earth's magnetic field
onehorse 0:39935bb3c1a1 732 hx = 2.0f * mx * (0.5f - q3q3 - q4q4) + 2.0f * my * (q2q3 - q1q4) + 2.0f * mz * (q2q4 + q1q3);
onehorse 0:39935bb3c1a1 733 hy = 2.0f * mx * (q2q3 + q1q4) + 2.0f * my * (0.5f - q2q2 - q4q4) + 2.0f * mz * (q3q4 - q1q2);
onehorse 0:39935bb3c1a1 734 bx = sqrt((hx * hx) + (hy * hy));
onehorse 0:39935bb3c1a1 735 bz = 2.0f * mx * (q2q4 - q1q3) + 2.0f * my * (q3q4 + q1q2) + 2.0f * mz * (0.5f - q2q2 - q3q3);
onehorse 0:39935bb3c1a1 736
onehorse 0:39935bb3c1a1 737 // Estimated direction of gravity and magnetic field
onehorse 0:39935bb3c1a1 738 vx = 2.0f * (q2q4 - q1q3);
onehorse 0:39935bb3c1a1 739 vy = 2.0f * (q1q2 + q3q4);
onehorse 0:39935bb3c1a1 740 vz = q1q1 - q2q2 - q3q3 + q4q4;
onehorse 0:39935bb3c1a1 741 wx = 2.0f * bx * (0.5f - q3q3 - q4q4) + 2.0f * bz * (q2q4 - q1q3);
onehorse 0:39935bb3c1a1 742 wy = 2.0f * bx * (q2q3 - q1q4) + 2.0f * bz * (q1q2 + q3q4);
onehorse 0:39935bb3c1a1 743 wz = 2.0f * bx * (q1q3 + q2q4) + 2.0f * bz * (0.5f - q2q2 - q3q3);
onehorse 0:39935bb3c1a1 744
onehorse 0:39935bb3c1a1 745 // Error is cross product between estimated direction and measured direction of gravity
onehorse 0:39935bb3c1a1 746 ex = (ay * vz - az * vy) + (my * wz - mz * wy);
onehorse 0:39935bb3c1a1 747 ey = (az * vx - ax * vz) + (mz * wx - mx * wz);
onehorse 0:39935bb3c1a1 748 ez = (ax * vy - ay * vx) + (mx * wy - my * wx);
onehorse 0:39935bb3c1a1 749 if (Ki > 0.0f)
onehorse 0:39935bb3c1a1 750 {
onehorse 0:39935bb3c1a1 751 eInt[0] += ex; // accumulate integral error
onehorse 0:39935bb3c1a1 752 eInt[1] += ey;
onehorse 0:39935bb3c1a1 753 eInt[2] += ez;
onehorse 0:39935bb3c1a1 754 }
onehorse 0:39935bb3c1a1 755 else
onehorse 0:39935bb3c1a1 756 {
onehorse 0:39935bb3c1a1 757 eInt[0] = 0.0f; // prevent integral wind up
onehorse 0:39935bb3c1a1 758 eInt[1] = 0.0f;
onehorse 0:39935bb3c1a1 759 eInt[2] = 0.0f;
onehorse 0:39935bb3c1a1 760 }
onehorse 0:39935bb3c1a1 761
onehorse 0:39935bb3c1a1 762 // Apply feedback terms
onehorse 0:39935bb3c1a1 763 gx = gx + Kp * ex + Ki * eInt[0];
onehorse 0:39935bb3c1a1 764 gy = gy + Kp * ey + Ki * eInt[1];
onehorse 0:39935bb3c1a1 765 gz = gz + Kp * ez + Ki * eInt[2];
onehorse 0:39935bb3c1a1 766
onehorse 0:39935bb3c1a1 767 // Integrate rate of change of quaternion
onehorse 0:39935bb3c1a1 768 pa = q2;
onehorse 0:39935bb3c1a1 769 pb = q3;
onehorse 0:39935bb3c1a1 770 pc = q4;
onehorse 0:39935bb3c1a1 771 q1 = q1 + (-q2 * gx - q3 * gy - q4 * gz) * (0.5f * deltat);
onehorse 0:39935bb3c1a1 772 q2 = pa + (q1 * gx + pb * gz - pc * gy) * (0.5f * deltat);
onehorse 0:39935bb3c1a1 773 q3 = pb + (q1 * gy - pa * gz + pc * gx) * (0.5f * deltat);
onehorse 0:39935bb3c1a1 774 q4 = pc + (q1 * gz + pa * gy - pb * gx) * (0.5f * deltat);
onehorse 0:39935bb3c1a1 775
onehorse 0:39935bb3c1a1 776 // Normalise quaternion
onehorse 0:39935bb3c1a1 777 norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4);
onehorse 0:39935bb3c1a1 778 norm = 1.0f / norm;
onehorse 0:39935bb3c1a1 779 q[0] = q1 * norm;
onehorse 0:39935bb3c1a1 780 q[1] = q2 * norm;
onehorse 0:39935bb3c1a1 781 q[2] = q3 * norm;
onehorse 0:39935bb3c1a1 782 q[3] = q4 * norm;
onehorse 0:39935bb3c1a1 783
onehorse 0:39935bb3c1a1 784 }
onehorse 0:39935bb3c1a1 785 };
onehorse 0:39935bb3c1a1 786 #endif