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