一応着地判定できます。

Dependencies:   mbed

Committer:
ponpoko1939
Date:
Sat Jul 14 08:15:05 2018 +0000
Revision:
0:1070e8be3721
ver ?

Who changed what in which revision?

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