Basic program to get the properly-scaled gyro and accelerometer data from a MPU-6050 6-axis motion sensor. Perform sensor fusion using Sebastian Madgwick's open-source IMU fusion filter. Running on the STM32F401 at 84 MHz achieved sensor fusion filter update rates of 5500 Hz. Additional info at https://github.com/kriswiner/MPU-6050.

Dependencies:   mbed

Committer:
onehorse
Date:
Sun May 25 04:51:50 2014 +0000
Revision:
0:65aa78c10981
Child:
1:cea9d83b8636
latest MPU-6050 program

Who changed what in which revision?

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