BME SmartLab
/
SmartCone
SmartCone Demo
MPU9250Mod.h@0:f86c91eb17cb, 2017-01-19 (annotated)
- Committer:
- mrcrsch
- Date:
- Thu Jan 19 13:25:53 2017 +0000
- Revision:
- 0:f86c91eb17cb
Init for publish;
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
mrcrsch | 0:f86c91eb17cb | 1 | #ifndef MPU9250_H |
mrcrsch | 0:f86c91eb17cb | 2 | #define MPU9250_H |
mrcrsch | 0:f86c91eb17cb | 3 | |
mrcrsch | 0:f86c91eb17cb | 4 | #include "mbed.h" |
mrcrsch | 0:f86c91eb17cb | 5 | #include "math.h" |
mrcrsch | 0:f86c91eb17cb | 6 | |
mrcrsch | 0:f86c91eb17cb | 7 | //const uint16_t this_node = 01; |
mrcrsch | 0:f86c91eb17cb | 8 | #define this_node 01 |
mrcrsch | 0:f86c91eb17cb | 9 | // See also MPU-9250 Register Map and Descriptions, Revision 4.0, RM-MPU-9250A-00, Rev. 1.4, 9/9/2013 for registers not listed in |
mrcrsch | 0:f86c91eb17cb | 10 | // above document; the MPU9250 and MPU9150 are virtually identical but the latter has a different register map |
mrcrsch | 0:f86c91eb17cb | 11 | // |
mrcrsch | 0:f86c91eb17cb | 12 | //Magnetometer Registers |
mrcrsch | 0:f86c91eb17cb | 13 | #define AK8963_ADDRESS 0x0C<<1 |
mrcrsch | 0:f86c91eb17cb | 14 | #define WHO_AM_I_AK8963 0x00 // should return 0x48 |
mrcrsch | 0:f86c91eb17cb | 15 | #define INFO 0x01 |
mrcrsch | 0:f86c91eb17cb | 16 | #define AK8963_ST1 0x02 // data ready status bit 0 |
mrcrsch | 0:f86c91eb17cb | 17 | #define AK8963_XOUT_L 0x03 // data |
mrcrsch | 0:f86c91eb17cb | 18 | #define AK8963_XOUT_H 0x04 |
mrcrsch | 0:f86c91eb17cb | 19 | #define AK8963_YOUT_L 0x05 |
mrcrsch | 0:f86c91eb17cb | 20 | #define AK8963_YOUT_H 0x06 |
mrcrsch | 0:f86c91eb17cb | 21 | #define AK8963_ZOUT_L 0x07 |
mrcrsch | 0:f86c91eb17cb | 22 | #define AK8963_ZOUT_H 0x08 |
mrcrsch | 0:f86c91eb17cb | 23 | #define AK8963_ST2 0x09 // Data overflow bit 3 and data read error status bit 2 |
mrcrsch | 0:f86c91eb17cb | 24 | #define AK8963_CNTL 0x0A // Power down (0000), single-measurement (0001), self-test (1000) and Fuse ROM (1111) modes on bits 3:0 |
mrcrsch | 0:f86c91eb17cb | 25 | #define AK8963_ASTC 0x0C // Self test control |
mrcrsch | 0:f86c91eb17cb | 26 | #define AK8963_I2CDIS 0x0F // I2C disable |
mrcrsch | 0:f86c91eb17cb | 27 | #define AK8963_ASAX 0x10 // Fuse ROM x-axis sensitivity adjustment value |
mrcrsch | 0:f86c91eb17cb | 28 | #define AK8963_ASAY 0x11 // Fuse ROM y-axis sensitivity adjustment value |
mrcrsch | 0:f86c91eb17cb | 29 | #define AK8963_ASAZ 0x12 // Fuse ROM z-axis sensitivity adjustment value |
mrcrsch | 0:f86c91eb17cb | 30 | |
mrcrsch | 0:f86c91eb17cb | 31 | #define SELF_TEST_X_GYRO 0x00 |
mrcrsch | 0:f86c91eb17cb | 32 | #define SELF_TEST_Y_GYRO 0x01 |
mrcrsch | 0:f86c91eb17cb | 33 | #define SELF_TEST_Z_GYRO 0x02 |
mrcrsch | 0:f86c91eb17cb | 34 | |
mrcrsch | 0:f86c91eb17cb | 35 | /*#define X_FINE_GAIN 0x03 // [7:0] fine gain |
mrcrsch | 0:f86c91eb17cb | 36 | #define Y_FINE_GAIN 0x04 |
mrcrsch | 0:f86c91eb17cb | 37 | #define Z_FINE_GAIN 0x05 |
mrcrsch | 0:f86c91eb17cb | 38 | #define XA_OFFSET_H 0x06 // User-defined trim values for accelerometer |
mrcrsch | 0:f86c91eb17cb | 39 | #define XA_OFFSET_L_TC 0x07 |
mrcrsch | 0:f86c91eb17cb | 40 | #define YA_OFFSET_H 0x08 |
mrcrsch | 0:f86c91eb17cb | 41 | #define YA_OFFSET_L_TC 0x09 |
mrcrsch | 0:f86c91eb17cb | 42 | #define ZA_OFFSET_H 0x0A |
mrcrsch | 0:f86c91eb17cb | 43 | #define ZA_OFFSET_L_TC 0x0B */ |
mrcrsch | 0:f86c91eb17cb | 44 | |
mrcrsch | 0:f86c91eb17cb | 45 | #define SELF_TEST_X_ACCEL 0x0D |
mrcrsch | 0:f86c91eb17cb | 46 | #define SELF_TEST_Y_ACCEL 0x0E |
mrcrsch | 0:f86c91eb17cb | 47 | #define SELF_TEST_Z_ACCEL 0x0F |
mrcrsch | 0:f86c91eb17cb | 48 | |
mrcrsch | 0:f86c91eb17cb | 49 | #define SELF_TEST_A 0x10 |
mrcrsch | 0:f86c91eb17cb | 50 | |
mrcrsch | 0:f86c91eb17cb | 51 | #define XG_OFFSET_H 0x13 // User-defined trim values for gyroscope |
mrcrsch | 0:f86c91eb17cb | 52 | #define XG_OFFSET_L 0x14 |
mrcrsch | 0:f86c91eb17cb | 53 | #define YG_OFFSET_H 0x15 |
mrcrsch | 0:f86c91eb17cb | 54 | #define YG_OFFSET_L 0x16 |
mrcrsch | 0:f86c91eb17cb | 55 | #define ZG_OFFSET_H 0x17 |
mrcrsch | 0:f86c91eb17cb | 56 | #define ZG_OFFSET_L 0x18 |
mrcrsch | 0:f86c91eb17cb | 57 | #define SMPLRT_DIV 0x19 |
mrcrsch | 0:f86c91eb17cb | 58 | #define CONFIG 0x1A |
mrcrsch | 0:f86c91eb17cb | 59 | #define GYRO_CONFIG 0x1B |
mrcrsch | 0:f86c91eb17cb | 60 | #define ACCEL_CONFIG 0x1C |
mrcrsch | 0:f86c91eb17cb | 61 | #define ACCEL_CONFIG2 0x1D |
mrcrsch | 0:f86c91eb17cb | 62 | #define LP_ACCEL_ODR 0x1E |
mrcrsch | 0:f86c91eb17cb | 63 | #define WOM_THR 0x1F |
mrcrsch | 0:f86c91eb17cb | 64 | |
mrcrsch | 0:f86c91eb17cb | 65 | #define MOT_DUR 0x20 // Duration counter threshold for motion interrupt generation, 1 kHz rate, LSB = 1 ms |
mrcrsch | 0:f86c91eb17cb | 66 | #define ZMOT_THR 0x21 // Zero-motion detection threshold bits [7:0] |
mrcrsch | 0:f86c91eb17cb | 67 | #define ZRMOT_DUR 0x22 // Duration counter threshold for zero motion interrupt generation, 16 Hz rate, LSB = 64 ms |
mrcrsch | 0:f86c91eb17cb | 68 | |
mrcrsch | 0:f86c91eb17cb | 69 | #define FIFO_EN 0x23 |
mrcrsch | 0:f86c91eb17cb | 70 | #define I2C_MST_CTRL 0x24 |
mrcrsch | 0:f86c91eb17cb | 71 | #define I2C_SLV0_ADDR 0x25 |
mrcrsch | 0:f86c91eb17cb | 72 | #define I2C_SLV0_REG 0x26 |
mrcrsch | 0:f86c91eb17cb | 73 | #define I2C_SLV0_CTRL 0x27 |
mrcrsch | 0:f86c91eb17cb | 74 | #define I2C_SLV1_ADDR 0x28 |
mrcrsch | 0:f86c91eb17cb | 75 | #define I2C_SLV1_REG 0x29 |
mrcrsch | 0:f86c91eb17cb | 76 | #define I2C_SLV1_CTRL 0x2A |
mrcrsch | 0:f86c91eb17cb | 77 | #define I2C_SLV2_ADDR 0x2B |
mrcrsch | 0:f86c91eb17cb | 78 | #define I2C_SLV2_REG 0x2C |
mrcrsch | 0:f86c91eb17cb | 79 | #define I2C_SLV2_CTRL 0x2D |
mrcrsch | 0:f86c91eb17cb | 80 | #define I2C_SLV3_ADDR 0x2E |
mrcrsch | 0:f86c91eb17cb | 81 | #define I2C_SLV3_REG 0x2F |
mrcrsch | 0:f86c91eb17cb | 82 | #define I2C_SLV3_CTRL 0x30 |
mrcrsch | 0:f86c91eb17cb | 83 | #define I2C_SLV4_ADDR 0x31 |
mrcrsch | 0:f86c91eb17cb | 84 | #define I2C_SLV4_REG 0x32 |
mrcrsch | 0:f86c91eb17cb | 85 | #define I2C_SLV4_DO 0x33 |
mrcrsch | 0:f86c91eb17cb | 86 | #define I2C_SLV4_CTRL 0x34 |
mrcrsch | 0:f86c91eb17cb | 87 | #define I2C_SLV4_DI 0x35 |
mrcrsch | 0:f86c91eb17cb | 88 | #define I2C_MST_STATUS 0x36 |
mrcrsch | 0:f86c91eb17cb | 89 | #define INT_PIN_CFG 0x37 |
mrcrsch | 0:f86c91eb17cb | 90 | #define INT_ENABLE 0x38 |
mrcrsch | 0:f86c91eb17cb | 91 | #define DMP_INT_STATUS 0x39 // Check DMP interrupt |
mrcrsch | 0:f86c91eb17cb | 92 | #define INT_STATUS 0x3A |
mrcrsch | 0:f86c91eb17cb | 93 | #define ACCEL_XOUT_H 0x3B |
mrcrsch | 0:f86c91eb17cb | 94 | #define ACCEL_XOUT_L 0x3C |
mrcrsch | 0:f86c91eb17cb | 95 | #define ACCEL_YOUT_H 0x3D |
mrcrsch | 0:f86c91eb17cb | 96 | #define ACCEL_YOUT_L 0x3E |
mrcrsch | 0:f86c91eb17cb | 97 | #define ACCEL_ZOUT_H 0x3F |
mrcrsch | 0:f86c91eb17cb | 98 | #define ACCEL_ZOUT_L 0x40 |
mrcrsch | 0:f86c91eb17cb | 99 | #define TEMP_OUT_H 0x41 |
mrcrsch | 0:f86c91eb17cb | 100 | #define TEMP_OUT_L 0x42 |
mrcrsch | 0:f86c91eb17cb | 101 | #define GYRO_XOUT_H 0x43 |
mrcrsch | 0:f86c91eb17cb | 102 | #define GYRO_XOUT_L 0x44 |
mrcrsch | 0:f86c91eb17cb | 103 | #define GYRO_YOUT_H 0x45 |
mrcrsch | 0:f86c91eb17cb | 104 | #define GYRO_YOUT_L 0x46 |
mrcrsch | 0:f86c91eb17cb | 105 | #define GYRO_ZOUT_H 0x47 |
mrcrsch | 0:f86c91eb17cb | 106 | #define GYRO_ZOUT_L 0x48 |
mrcrsch | 0:f86c91eb17cb | 107 | #define EXT_SENS_DATA_00 0x49 |
mrcrsch | 0:f86c91eb17cb | 108 | #define EXT_SENS_DATA_01 0x4A |
mrcrsch | 0:f86c91eb17cb | 109 | #define EXT_SENS_DATA_02 0x4B |
mrcrsch | 0:f86c91eb17cb | 110 | #define EXT_SENS_DATA_03 0x4C |
mrcrsch | 0:f86c91eb17cb | 111 | #define EXT_SENS_DATA_04 0x4D |
mrcrsch | 0:f86c91eb17cb | 112 | #define EXT_SENS_DATA_05 0x4E |
mrcrsch | 0:f86c91eb17cb | 113 | #define EXT_SENS_DATA_06 0x4F |
mrcrsch | 0:f86c91eb17cb | 114 | #define EXT_SENS_DATA_07 0x50 |
mrcrsch | 0:f86c91eb17cb | 115 | #define EXT_SENS_DATA_08 0x51 |
mrcrsch | 0:f86c91eb17cb | 116 | #define EXT_SENS_DATA_09 0x52 |
mrcrsch | 0:f86c91eb17cb | 117 | #define EXT_SENS_DATA_10 0x53 |
mrcrsch | 0:f86c91eb17cb | 118 | #define EXT_SENS_DATA_11 0x54 |
mrcrsch | 0:f86c91eb17cb | 119 | #define EXT_SENS_DATA_12 0x55 |
mrcrsch | 0:f86c91eb17cb | 120 | #define EXT_SENS_DATA_13 0x56 |
mrcrsch | 0:f86c91eb17cb | 121 | #define EXT_SENS_DATA_14 0x57 |
mrcrsch | 0:f86c91eb17cb | 122 | #define EXT_SENS_DATA_15 0x58 |
mrcrsch | 0:f86c91eb17cb | 123 | #define EXT_SENS_DATA_16 0x59 |
mrcrsch | 0:f86c91eb17cb | 124 | #define EXT_SENS_DATA_17 0x5A |
mrcrsch | 0:f86c91eb17cb | 125 | #define EXT_SENS_DATA_18 0x5B |
mrcrsch | 0:f86c91eb17cb | 126 | #define EXT_SENS_DATA_19 0x5C |
mrcrsch | 0:f86c91eb17cb | 127 | #define EXT_SENS_DATA_20 0x5D |
mrcrsch | 0:f86c91eb17cb | 128 | #define EXT_SENS_DATA_21 0x5E |
mrcrsch | 0:f86c91eb17cb | 129 | #define EXT_SENS_DATA_22 0x5F |
mrcrsch | 0:f86c91eb17cb | 130 | #define EXT_SENS_DATA_23 0x60 |
mrcrsch | 0:f86c91eb17cb | 131 | #define MOT_DETECT_STATUS 0x61 |
mrcrsch | 0:f86c91eb17cb | 132 | #define I2C_SLV0_DO 0x63 |
mrcrsch | 0:f86c91eb17cb | 133 | #define I2C_SLV1_DO 0x64 |
mrcrsch | 0:f86c91eb17cb | 134 | #define I2C_SLV2_DO 0x65 |
mrcrsch | 0:f86c91eb17cb | 135 | #define I2C_SLV3_DO 0x66 |
mrcrsch | 0:f86c91eb17cb | 136 | #define I2C_MST_DELAY_CTRL 0x67 |
mrcrsch | 0:f86c91eb17cb | 137 | #define SIGNAL_PATH_RESET 0x68 |
mrcrsch | 0:f86c91eb17cb | 138 | #define MOT_DETECT_CTRL 0x69 |
mrcrsch | 0:f86c91eb17cb | 139 | #define USER_CTRL 0x6A // Bit 7 enable DMP, bit 3 reset DMP |
mrcrsch | 0:f86c91eb17cb | 140 | #define PWR_MGMT_1 0x6B // Device defaults to the SLEEP mode |
mrcrsch | 0:f86c91eb17cb | 141 | #define PWR_MGMT_2 0x6C |
mrcrsch | 0:f86c91eb17cb | 142 | #define DMP_BANK 0x6D // Activates a specific bank in the DMP |
mrcrsch | 0:f86c91eb17cb | 143 | #define DMP_RW_PNT 0x6E // Set read/write pointer to a specific start address in specified DMP bank |
mrcrsch | 0:f86c91eb17cb | 144 | #define DMP_REG 0x6F // Register in DMP from which to read or to which to write |
mrcrsch | 0:f86c91eb17cb | 145 | #define DMP_REG_1 0x70 |
mrcrsch | 0:f86c91eb17cb | 146 | #define DMP_REG_2 0x71 |
mrcrsch | 0:f86c91eb17cb | 147 | #define FIFO_COUNTH 0x72 |
mrcrsch | 0:f86c91eb17cb | 148 | #define FIFO_COUNTL 0x73 |
mrcrsch | 0:f86c91eb17cb | 149 | #define FIFO_R_W 0x74 |
mrcrsch | 0:f86c91eb17cb | 150 | #define WHO_AM_I_MPU9250 0x75 // Should return 0x71 |
mrcrsch | 0:f86c91eb17cb | 151 | #define XA_OFFSET_H 0x77 |
mrcrsch | 0:f86c91eb17cb | 152 | #define XA_OFFSET_L 0x78 |
mrcrsch | 0:f86c91eb17cb | 153 | #define YA_OFFSET_H 0x7A |
mrcrsch | 0:f86c91eb17cb | 154 | #define YA_OFFSET_L 0x7B |
mrcrsch | 0:f86c91eb17cb | 155 | #define ZA_OFFSET_H 0x7D |
mrcrsch | 0:f86c91eb17cb | 156 | #define ZA_OFFSET_L 0x7E |
mrcrsch | 0:f86c91eb17cb | 157 | |
mrcrsch | 0:f86c91eb17cb | 158 | // Using the MSENSR-9250 breakout board, ADO is set to 0 |
mrcrsch | 0:f86c91eb17cb | 159 | // Seven-bit device address is 110100 for ADO = 0 and 110101 for ADO = 1 |
mrcrsch | 0:f86c91eb17cb | 160 | //mbed uses the eight-bit device address, so shift seven-bit addresses left by one! |
mrcrsch | 0:f86c91eb17cb | 161 | #define ADO 0 |
mrcrsch | 0:f86c91eb17cb | 162 | #if ADO |
mrcrsch | 0:f86c91eb17cb | 163 | #define MPU9250_ADDRESS 0x69<<1 // Device address when ADO = 1 |
mrcrsch | 0:f86c91eb17cb | 164 | #else |
mrcrsch | 0:f86c91eb17cb | 165 | #define MPU9250_ADDRESS 0x68<<1 // Device address when ADO = 0 |
mrcrsch | 0:f86c91eb17cb | 166 | #endif |
mrcrsch | 0:f86c91eb17cb | 167 | |
mrcrsch | 0:f86c91eb17cb | 168 | // Set initial input parameters |
mrcrsch | 0:f86c91eb17cb | 169 | enum Ascale { |
mrcrsch | 0:f86c91eb17cb | 170 | AFS_2G = 0, |
mrcrsch | 0:f86c91eb17cb | 171 | AFS_4G, |
mrcrsch | 0:f86c91eb17cb | 172 | AFS_8G, |
mrcrsch | 0:f86c91eb17cb | 173 | AFS_16G |
mrcrsch | 0:f86c91eb17cb | 174 | }; |
mrcrsch | 0:f86c91eb17cb | 175 | |
mrcrsch | 0:f86c91eb17cb | 176 | enum Gscale { |
mrcrsch | 0:f86c91eb17cb | 177 | GFS_250DPS = 0, |
mrcrsch | 0:f86c91eb17cb | 178 | GFS_500DPS, |
mrcrsch | 0:f86c91eb17cb | 179 | GFS_1000DPS, |
mrcrsch | 0:f86c91eb17cb | 180 | GFS_2000DPS |
mrcrsch | 0:f86c91eb17cb | 181 | }; |
mrcrsch | 0:f86c91eb17cb | 182 | |
mrcrsch | 0:f86c91eb17cb | 183 | enum Mscale { |
mrcrsch | 0:f86c91eb17cb | 184 | MFS_14BITS = 0, // 0.6 mG per LSB |
mrcrsch | 0:f86c91eb17cb | 185 | MFS_16BITS // 0.15 mG per LSB |
mrcrsch | 0:f86c91eb17cb | 186 | }; |
mrcrsch | 0:f86c91eb17cb | 187 | |
mrcrsch | 0:f86c91eb17cb | 188 | uint8_t Ascale = AFS_8G; // AFS_2G, AFS_4G, AFS_8G, AFS_16G |
mrcrsch | 0:f86c91eb17cb | 189 | uint8_t Gscale = GFS_2000DPS; // GFS_250DPS, GFS_500DPS, GFS_1000DPS, GFS_2000DPS |
mrcrsch | 0:f86c91eb17cb | 190 | uint8_t Mscale = MFS_16BITS; // MFS_14BITS or MFS_16BITS, 14-bit or 16-bit magnetometer resolution |
mrcrsch | 0:f86c91eb17cb | 191 | uint8_t Mmode = 0x06; // Either 8 Hz 0x02) or 100 Hz (0x06) magnetometer data ODR |
mrcrsch | 0:f86c91eb17cb | 192 | float aRes, gRes, mRes; // scale resolutions per LSB for the sensors |
mrcrsch | 0:f86c91eb17cb | 193 | |
mrcrsch | 0:f86c91eb17cb | 194 | //Set up I2C, (SDA,SCL) |
mrcrsch | 0:f86c91eb17cb | 195 | //I2C i2c(PB_9, PB_8); |
mrcrsch | 0:f86c91eb17cb | 196 | I2C i2c(PF_0,PF_1); |
mrcrsch | 0:f86c91eb17cb | 197 | |
mrcrsch | 0:f86c91eb17cb | 198 | |
mrcrsch | 0:f86c91eb17cb | 199 | float magbias[3] = {303.12, 163.22, -259.35}, magCalibration[3] = {0,0,0}; // Factory mag calibration and mag bias |
mrcrsch | 0:f86c91eb17cb | 200 | float magscale[3] = {1.16,0.987234,0.888889}; |
mrcrsch | 0:f86c91eb17cb | 201 | float gyroBias[3] = {0.326364,-0.87681,0.723182}, accelBias[3] = {-0.00906,0.009605,0.002286}; // Bias corrections for gyro and accelerometer |
mrcrsch | 0:f86c91eb17cb | 202 | |
mrcrsch | 0:f86c91eb17cb | 203 | /* |
mrcrsch | 0:f86c91eb17cb | 204 | #if this_node == 01 |
mrcrsch | 0:f86c91eb17cb | 205 | float magbias[3] = {303.12, 163.22, -259.35}, magCalibration[3] = {0,0,0}; // Factory mag calibration and mag bias |
mrcrsch | 0:f86c91eb17cb | 206 | float magscale[3] = {1.16,0.987234,0.888889}; |
mrcrsch | 0:f86c91eb17cb | 207 | float gyroBias[3] = {0.326364,-0.87681,0.723182}, accelBias[3] = {-0.00906,0.009605,0.002286}; // Bias corrections for gyro and accelerometer |
mrcrsch | 0:f86c91eb17cb | 208 | #elif this_node == 02 |
mrcrsch | 0:f86c91eb17cb | 209 | float magbias[3] = {152.937, 284.675, 32.2063}, magCalibration[3] = {0,0,0}; // Factory mag calibration and mag bias |
mrcrsch | 0:f86c91eb17cb | 210 | float magscale[3] = {1.05367, 0.986772, 0.963824}; |
mrcrsch | 0:f86c91eb17cb | 211 | //float gyroBias[3] = {2.16792601,-3.441743604,-11.80535044}, accelBias[3] = {0.063996427,-0.04823691,-0.045249821}; |
mrcrsch | 0:f86c91eb17cb | 212 | float gyroBias[3] = {2.450195,-1.63298,-18.4074}, accelBias[3] = {0.021225,0.018935,-0.05172}; |
mrcrsch | 0:f86c91eb17cb | 213 | #elif this_node == 03 //racket |
mrcrsch | 0:f86c91eb17cb | 214 | float magbias[3] = {263.908875, 440.263977, -235.16362}, magCalibration[3] = {0,0,0}; // Factory mag calibration and mag bias |
mrcrsch | 0:f86c91eb17cb | 215 | float magscale[3] = {1.013227, 0.997396, 0.989664}; |
mrcrsch | 0:f86c91eb17cb | 216 | float gyroBias[3] = {-1.12645,0.154036,0.416789}, accelBias[3] = {-0.009199,-0.03983,-0.00774}; |
mrcrsch | 0:f86c91eb17cb | 217 | #endif |
mrcrsch | 0:f86c91eb17cb | 218 | */ |
mrcrsch | 0:f86c91eb17cb | 219 | |
mrcrsch | 0:f86c91eb17cb | 220 | |
mrcrsch | 0:f86c91eb17cb | 221 | // Pin definitions |
mrcrsch | 0:f86c91eb17cb | 222 | int intPin = 12; // These can be changed, 2 and 3 are the Arduinos ext int pins |
mrcrsch | 0:f86c91eb17cb | 223 | |
mrcrsch | 0:f86c91eb17cb | 224 | int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output |
mrcrsch | 0:f86c91eb17cb | 225 | int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output |
mrcrsch | 0:f86c91eb17cb | 226 | int16_t magCount[3]; // Stores the 16-bit signed magnetometer sensor output |
mrcrsch | 0:f86c91eb17cb | 227 | float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values |
mrcrsch | 0:f86c91eb17cb | 228 | int16_t tempCount; // Stores the real internal chip temperature in degrees Celsius |
mrcrsch | 0:f86c91eb17cb | 229 | float temperature; |
mrcrsch | 0:f86c91eb17cb | 230 | float SelfTest[6]; |
mrcrsch | 0:f86c91eb17cb | 231 | |
mrcrsch | 0:f86c91eb17cb | 232 | int delt_t = 0; // used to control display output rate |
mrcrsch | 0:f86c91eb17cb | 233 | int count = 0; // used to control display output rate |
mrcrsch | 0:f86c91eb17cb | 234 | |
mrcrsch | 0:f86c91eb17cb | 235 | // parameters for 6 DoF sensor fusion calculations |
mrcrsch | 0:f86c91eb17cb | 236 | float PI = 3.14159265358979323846f; |
mrcrsch | 0:f86c91eb17cb | 237 | float GyroMeasError = PI * (40.0f / 180.0f); //60 volt // gyroscope measurement error in rads/s (start at 60 deg/s), then reduce after ~10 s to 3 |
mrcrsch | 0:f86c91eb17cb | 238 | float beta = sqrt(3.0f / 4.0f) * GyroMeasError; //3 volt // compute beta |
mrcrsch | 0:f86c91eb17cb | 239 | float GyroMeasDrift = PI * (0.0f / 180.0f); //1.0 volt // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) |
mrcrsch | 0:f86c91eb17cb | 240 | 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 |
mrcrsch | 0:f86c91eb17cb | 241 | #define Kp 2.0f //* 5.0f // these are the free parameters in the Mahony filter and fusion scheme, Kp for proportional feedback, Ki for integral |
mrcrsch | 0:f86c91eb17cb | 242 | #define Ki 0.005f |
mrcrsch | 0:f86c91eb17cb | 243 | |
mrcrsch | 0:f86c91eb17cb | 244 | float pitch, yaw, roll; |
mrcrsch | 0:f86c91eb17cb | 245 | float deltat = 0.0f; // integration interval for both filter schemes |
mrcrsch | 0:f86c91eb17cb | 246 | int lastUpdate = 0, firstUpdate = 0, Now = 0; // used to calculate integration interval // used to calculate integration interval |
mrcrsch | 0:f86c91eb17cb | 247 | float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion |
mrcrsch | 0:f86c91eb17cb | 248 | float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method |
mrcrsch | 0:f86c91eb17cb | 249 | |
mrcrsch | 0:f86c91eb17cb | 250 | class MPU9250 { |
mrcrsch | 0:f86c91eb17cb | 251 | |
mrcrsch | 0:f86c91eb17cb | 252 | protected: |
mrcrsch | 0:f86c91eb17cb | 253 | |
mrcrsch | 0:f86c91eb17cb | 254 | public: |
mrcrsch | 0:f86c91eb17cb | 255 | //=================================================================================================================== |
mrcrsch | 0:f86c91eb17cb | 256 | //====== Set of useful function to access acceleratio, gyroscope, and temperature data |
mrcrsch | 0:f86c91eb17cb | 257 | //=================================================================================================================== |
mrcrsch | 0:f86c91eb17cb | 258 | |
mrcrsch | 0:f86c91eb17cb | 259 | void writeByte(uint8_t address, uint8_t subAddress, uint8_t data) |
mrcrsch | 0:f86c91eb17cb | 260 | { |
mrcrsch | 0:f86c91eb17cb | 261 | char data_write[2]; |
mrcrsch | 0:f86c91eb17cb | 262 | data_write[0] = subAddress; |
mrcrsch | 0:f86c91eb17cb | 263 | data_write[1] = data; |
mrcrsch | 0:f86c91eb17cb | 264 | i2c.write(address, data_write, 2, 0); |
mrcrsch | 0:f86c91eb17cb | 265 | } |
mrcrsch | 0:f86c91eb17cb | 266 | |
mrcrsch | 0:f86c91eb17cb | 267 | char readByte(uint8_t address, uint8_t subAddress) |
mrcrsch | 0:f86c91eb17cb | 268 | { |
mrcrsch | 0:f86c91eb17cb | 269 | char data[1]; // `data` will store the register data |
mrcrsch | 0:f86c91eb17cb | 270 | char data_write[1]; |
mrcrsch | 0:f86c91eb17cb | 271 | data_write[0] = subAddress; |
mrcrsch | 0:f86c91eb17cb | 272 | i2c.write(address, data_write, 1, 1); // no stop |
mrcrsch | 0:f86c91eb17cb | 273 | i2c.read(address, data, 1, 0); |
mrcrsch | 0:f86c91eb17cb | 274 | return data[0]; |
mrcrsch | 0:f86c91eb17cb | 275 | } |
mrcrsch | 0:f86c91eb17cb | 276 | |
mrcrsch | 0:f86c91eb17cb | 277 | void readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) |
mrcrsch | 0:f86c91eb17cb | 278 | { |
mrcrsch | 0:f86c91eb17cb | 279 | char data[14]; |
mrcrsch | 0:f86c91eb17cb | 280 | char data_write[1]; |
mrcrsch | 0:f86c91eb17cb | 281 | data_write[0] = subAddress; |
mrcrsch | 0:f86c91eb17cb | 282 | i2c.write(address, data_write, 1, 1); // no stop |
mrcrsch | 0:f86c91eb17cb | 283 | i2c.read(address, data, count, 0); |
mrcrsch | 0:f86c91eb17cb | 284 | for(int ii = 0; ii < count; ii++) { |
mrcrsch | 0:f86c91eb17cb | 285 | dest[ii] = data[ii]; |
mrcrsch | 0:f86c91eb17cb | 286 | } |
mrcrsch | 0:f86c91eb17cb | 287 | } |
mrcrsch | 0:f86c91eb17cb | 288 | |
mrcrsch | 0:f86c91eb17cb | 289 | |
mrcrsch | 0:f86c91eb17cb | 290 | void getMres() { |
mrcrsch | 0:f86c91eb17cb | 291 | switch (Mscale) |
mrcrsch | 0:f86c91eb17cb | 292 | { |
mrcrsch | 0:f86c91eb17cb | 293 | // Possible magnetometer scales (and their register bit settings) are: |
mrcrsch | 0:f86c91eb17cb | 294 | // 14 bit resolution (0) and 16 bit resolution (1) |
mrcrsch | 0:f86c91eb17cb | 295 | case MFS_14BITS: |
mrcrsch | 0:f86c91eb17cb | 296 | mRes = 10.0*4219.0/8190.0; // Proper scale to return milliGauss |
mrcrsch | 0:f86c91eb17cb | 297 | break; |
mrcrsch | 0:f86c91eb17cb | 298 | case MFS_16BITS: |
mrcrsch | 0:f86c91eb17cb | 299 | mRes = 10.0*4219.0/32760.0; // Proper scale to return milliGauss |
mrcrsch | 0:f86c91eb17cb | 300 | break; |
mrcrsch | 0:f86c91eb17cb | 301 | } |
mrcrsch | 0:f86c91eb17cb | 302 | } |
mrcrsch | 0:f86c91eb17cb | 303 | |
mrcrsch | 0:f86c91eb17cb | 304 | |
mrcrsch | 0:f86c91eb17cb | 305 | void getGres() { |
mrcrsch | 0:f86c91eb17cb | 306 | switch (Gscale) |
mrcrsch | 0:f86c91eb17cb | 307 | { |
mrcrsch | 0:f86c91eb17cb | 308 | // Possible gyro scales (and their register bit settings) are: |
mrcrsch | 0:f86c91eb17cb | 309 | // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS (11). |
mrcrsch | 0:f86c91eb17cb | 310 | // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: |
mrcrsch | 0:f86c91eb17cb | 311 | case GFS_250DPS: |
mrcrsch | 0:f86c91eb17cb | 312 | gRes = 250.0/32768.0; |
mrcrsch | 0:f86c91eb17cb | 313 | break; |
mrcrsch | 0:f86c91eb17cb | 314 | case GFS_500DPS: |
mrcrsch | 0:f86c91eb17cb | 315 | gRes = 500.0/32768.0; |
mrcrsch | 0:f86c91eb17cb | 316 | break; |
mrcrsch | 0:f86c91eb17cb | 317 | case GFS_1000DPS: |
mrcrsch | 0:f86c91eb17cb | 318 | gRes = 1000.0/32768.0; |
mrcrsch | 0:f86c91eb17cb | 319 | break; |
mrcrsch | 0:f86c91eb17cb | 320 | case GFS_2000DPS: |
mrcrsch | 0:f86c91eb17cb | 321 | gRes = 2000.0/32768.0; |
mrcrsch | 0:f86c91eb17cb | 322 | break; |
mrcrsch | 0:f86c91eb17cb | 323 | } |
mrcrsch | 0:f86c91eb17cb | 324 | } |
mrcrsch | 0:f86c91eb17cb | 325 | |
mrcrsch | 0:f86c91eb17cb | 326 | |
mrcrsch | 0:f86c91eb17cb | 327 | void getAres() { |
mrcrsch | 0:f86c91eb17cb | 328 | switch (Ascale) |
mrcrsch | 0:f86c91eb17cb | 329 | { |
mrcrsch | 0:f86c91eb17cb | 330 | // Possible accelerometer scales (and their register bit settings) are: |
mrcrsch | 0:f86c91eb17cb | 331 | // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs (11). |
mrcrsch | 0:f86c91eb17cb | 332 | // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: |
mrcrsch | 0:f86c91eb17cb | 333 | case AFS_2G: |
mrcrsch | 0:f86c91eb17cb | 334 | aRes = 2.0/32768.0; |
mrcrsch | 0:f86c91eb17cb | 335 | break; |
mrcrsch | 0:f86c91eb17cb | 336 | case AFS_4G: |
mrcrsch | 0:f86c91eb17cb | 337 | aRes = 4.0/32768.0; |
mrcrsch | 0:f86c91eb17cb | 338 | break; |
mrcrsch | 0:f86c91eb17cb | 339 | case AFS_8G: |
mrcrsch | 0:f86c91eb17cb | 340 | aRes = 8.0/32768.0; |
mrcrsch | 0:f86c91eb17cb | 341 | break; |
mrcrsch | 0:f86c91eb17cb | 342 | case AFS_16G: |
mrcrsch | 0:f86c91eb17cb | 343 | aRes = 16.0/32768.0; |
mrcrsch | 0:f86c91eb17cb | 344 | break; |
mrcrsch | 0:f86c91eb17cb | 345 | } |
mrcrsch | 0:f86c91eb17cb | 346 | } |
mrcrsch | 0:f86c91eb17cb | 347 | |
mrcrsch | 0:f86c91eb17cb | 348 | |
mrcrsch | 0:f86c91eb17cb | 349 | void readAccelData(int16_t * destination) |
mrcrsch | 0:f86c91eb17cb | 350 | { |
mrcrsch | 0:f86c91eb17cb | 351 | uint8_t rawData[6]; // x/y/z accel register data stored here |
mrcrsch | 0:f86c91eb17cb | 352 | readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array |
mrcrsch | 0:f86c91eb17cb | 353 | destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value |
mrcrsch | 0:f86c91eb17cb | 354 | destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; |
mrcrsch | 0:f86c91eb17cb | 355 | destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; |
mrcrsch | 0:f86c91eb17cb | 356 | } |
mrcrsch | 0:f86c91eb17cb | 357 | |
mrcrsch | 0:f86c91eb17cb | 358 | void readGyroData(int16_t * destination) |
mrcrsch | 0:f86c91eb17cb | 359 | { |
mrcrsch | 0:f86c91eb17cb | 360 | uint8_t rawData[6]; // x/y/z gyro register data stored here |
mrcrsch | 0:f86c91eb17cb | 361 | readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array |
mrcrsch | 0:f86c91eb17cb | 362 | destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value |
mrcrsch | 0:f86c91eb17cb | 363 | destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; |
mrcrsch | 0:f86c91eb17cb | 364 | destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; |
mrcrsch | 0:f86c91eb17cb | 365 | } |
mrcrsch | 0:f86c91eb17cb | 366 | |
mrcrsch | 0:f86c91eb17cb | 367 | void readMagData(int16_t * destination) |
mrcrsch | 0:f86c91eb17cb | 368 | { |
mrcrsch | 0:f86c91eb17cb | 369 | uint8_t rawData[7]; // x/y/z gyro register data, ST2 register stored here, must read ST2 at end of data acquisition |
mrcrsch | 0:f86c91eb17cb | 370 | if(readByte(AK8963_ADDRESS, AK8963_ST1) & 0x01) { // wait for magnetometer data ready bit to be set |
mrcrsch | 0:f86c91eb17cb | 371 | readBytes(AK8963_ADDRESS, AK8963_XOUT_L, 7, &rawData[0]); // Read the six raw data and ST2 registers sequentially into data array |
mrcrsch | 0:f86c91eb17cb | 372 | uint8_t c = rawData[6]; // End data read by reading ST2 register |
mrcrsch | 0:f86c91eb17cb | 373 | if(!(c & 0x08)) { // Check if magnetic sensor overflow set, if not then report data |
mrcrsch | 0:f86c91eb17cb | 374 | destination[0] = (int16_t)(((int16_t)rawData[1] << 8) | rawData[0]); // Turn the MSB and LSB into a signed 16-bit value |
mrcrsch | 0:f86c91eb17cb | 375 | destination[1] = (int16_t)(((int16_t)rawData[3] << 8) | rawData[2]) ; // Data stored as little Endian |
mrcrsch | 0:f86c91eb17cb | 376 | destination[2] = (int16_t)(((int16_t)rawData[5] << 8) | rawData[4]) ; |
mrcrsch | 0:f86c91eb17cb | 377 | } |
mrcrsch | 0:f86c91eb17cb | 378 | } |
mrcrsch | 0:f86c91eb17cb | 379 | } |
mrcrsch | 0:f86c91eb17cb | 380 | |
mrcrsch | 0:f86c91eb17cb | 381 | int16_t readTempData() |
mrcrsch | 0:f86c91eb17cb | 382 | { |
mrcrsch | 0:f86c91eb17cb | 383 | uint8_t rawData[2]; // x/y/z gyro register data stored here |
mrcrsch | 0:f86c91eb17cb | 384 | readBytes(MPU9250_ADDRESS, TEMP_OUT_H, 2, &rawData[0]); // Read the two raw data registers sequentially into data array |
mrcrsch | 0:f86c91eb17cb | 385 | return (int16_t)(((int16_t)rawData[0]) << 8 | rawData[1]) ; // Turn the MSB and LSB into a 16-bit value |
mrcrsch | 0:f86c91eb17cb | 386 | } |
mrcrsch | 0:f86c91eb17cb | 387 | |
mrcrsch | 0:f86c91eb17cb | 388 | |
mrcrsch | 0:f86c91eb17cb | 389 | void resetMPU9250() { |
mrcrsch | 0:f86c91eb17cb | 390 | // reset device |
mrcrsch | 0:f86c91eb17cb | 391 | writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device |
mrcrsch | 0:f86c91eb17cb | 392 | wait(0.1); |
mrcrsch | 0:f86c91eb17cb | 393 | } |
mrcrsch | 0:f86c91eb17cb | 394 | |
mrcrsch | 0:f86c91eb17cb | 395 | |
mrcrsch | 0:f86c91eb17cb | 396 | void initMPU9250() |
mrcrsch | 0:f86c91eb17cb | 397 | { |
mrcrsch | 0:f86c91eb17cb | 398 | // Initialize MPU9250 device |
mrcrsch | 0:f86c91eb17cb | 399 | // wake up device |
mrcrsch | 0:f86c91eb17cb | 400 | writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors |
mrcrsch | 0:f86c91eb17cb | 401 | wait(0.1); // Delay 100 ms for PLL to get established on x-axis gyro; should check for PLL ready interrupt |
mrcrsch | 0:f86c91eb17cb | 402 | |
mrcrsch | 0:f86c91eb17cb | 403 | // get stable time source |
mrcrsch | 0:f86c91eb17cb | 404 | writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01); // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001 |
mrcrsch | 0:f86c91eb17cb | 405 | |
mrcrsch | 0:f86c91eb17cb | 406 | // Configure Gyro and Accelerometer |
mrcrsch | 0:f86c91eb17cb | 407 | // Disable FSYNC and set accelerometer and gyro bandwidth to 44 and 42 Hz, respectively; |
mrcrsch | 0:f86c91eb17cb | 408 | // DLPF_CFG = bits 2:0 = 010; this sets the sample rate at 1 kHz for both |
mrcrsch | 0:f86c91eb17cb | 409 | // Maximum delay is 4.9 ms which is just over a 200 Hz maximum rate |
mrcrsch | 0:f86c91eb17cb | 410 | writeByte(MPU9250_ADDRESS, CONFIG, 0x01 ); |
mrcrsch | 0:f86c91eb17cb | 411 | |
mrcrsch | 0:f86c91eb17cb | 412 | // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV) |
mrcrsch | 0:f86c91eb17cb | 413 | writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x09); // Use a 200 Hz rate; the same rate set in CONFIG above |
mrcrsch | 0:f86c91eb17cb | 414 | |
mrcrsch | 0:f86c91eb17cb | 415 | // Set gyroscope full scale range |
mrcrsch | 0:f86c91eb17cb | 416 | // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3 |
mrcrsch | 0:f86c91eb17cb | 417 | uint8_t c = readByte(MPU9250_ADDRESS, GYRO_CONFIG); |
mrcrsch | 0:f86c91eb17cb | 418 | writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] |
mrcrsch | 0:f86c91eb17cb | 419 | writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c & ~0x18); // Clear AFS bits [4:3] |
mrcrsch | 0:f86c91eb17cb | 420 | writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c | Gscale << 3); // Set full scale range for the gyro |
mrcrsch | 0:f86c91eb17cb | 421 | |
mrcrsch | 0:f86c91eb17cb | 422 | // Set accelerometer configuration |
mrcrsch | 0:f86c91eb17cb | 423 | c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG); |
mrcrsch | 0:f86c91eb17cb | 424 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] |
mrcrsch | 0:f86c91eb17cb | 425 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c & ~0x18); // Clear AFS bits [4:3] |
mrcrsch | 0:f86c91eb17cb | 426 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c | Ascale << 3); // Set full scale range for the accelerometer |
mrcrsch | 0:f86c91eb17cb | 427 | |
mrcrsch | 0:f86c91eb17cb | 428 | // Set accelerometer sample rate configuration |
mrcrsch | 0:f86c91eb17cb | 429 | // It is possible to get a 4 kHz sample rate from the accelerometer by choosing 1 for |
mrcrsch | 0:f86c91eb17cb | 430 | // accel_fchoice_b bit [3]; in this case the bandwidth is 1.13 kHz |
mrcrsch | 0:f86c91eb17cb | 431 | c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG2); |
mrcrsch | 0:f86c91eb17cb | 432 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c & ~0x0F); // Clear accel_fchoice_b (bit 3) and A_DLPFG (bits [2:0]) |
mrcrsch | 0:f86c91eb17cb | 433 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c | 0x01); // Set accelerometer rate to 1 kHz and bandwidth to 41 Hz |
mrcrsch | 0:f86c91eb17cb | 434 | |
mrcrsch | 0:f86c91eb17cb | 435 | // The accelerometer, gyro, and thermometer are set to 1 kHz sample rates, |
mrcrsch | 0:f86c91eb17cb | 436 | // but all these rates are further reduced by a factor of 5 to 200 Hz because of the SMPLRT_DIV setting |
mrcrsch | 0:f86c91eb17cb | 437 | |
mrcrsch | 0:f86c91eb17cb | 438 | // Configure Interrupts and Bypass Enable |
mrcrsch | 0:f86c91eb17cb | 439 | // Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips |
mrcrsch | 0:f86c91eb17cb | 440 | // can join the I2C bus and all can be controlled by the Arduino as master |
mrcrsch | 0:f86c91eb17cb | 441 | writeByte(MPU9250_ADDRESS, INT_PIN_CFG, 0x22); |
mrcrsch | 0:f86c91eb17cb | 442 | writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x01); // Enable data ready (bit 0) interrupt |
mrcrsch | 0:f86c91eb17cb | 443 | } |
mrcrsch | 0:f86c91eb17cb | 444 | |
mrcrsch | 0:f86c91eb17cb | 445 | |
mrcrsch | 0:f86c91eb17cb | 446 | |
mrcrsch | 0:f86c91eb17cb | 447 | |
mrcrsch | 0:f86c91eb17cb | 448 | |
mrcrsch | 0:f86c91eb17cb | 449 | }; |
mrcrsch | 0:f86c91eb17cb | 450 | |
mrcrsch | 0:f86c91eb17cb | 451 | |
mrcrsch | 0:f86c91eb17cb | 452 | |
mrcrsch | 0:f86c91eb17cb | 453 | |
mrcrsch | 0:f86c91eb17cb | 454 | |
mrcrsch | 0:f86c91eb17cb | 455 | |
mrcrsch | 0:f86c91eb17cb | 456 | #endif |