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