servo_tread + imu

Dependencies:   Servo mbed-rtos mbed

Fork of Turtlecase by TurtleBot

Committer:
worasuchad
Date:
Tue Feb 20 11:06:35 2018 +0000
Revision:
1:5609c1795245
servo + imu

Who changed what in which revision?

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