Details | Last modification | View Log | RSS feed
Rev | Author | Line No. | Line |
---|---|---|---|
2194 | - | 1 | /* |
2 | MPU6050 lib 0x02 |
||
3 | |||
4 | copyright (c) Davide Gironi, 2012 |
||
5 | |||
6 | Released under GPLv3. |
||
7 | Please refer to LICENSE file for licensing information. |
||
8 | |||
9 | References: |
||
10 | - most of the code is a port of the arduino mpu6050 library by Jeff Rowberg |
||
11 | https://github.com/jrowberg/i2cdevlib |
||
12 | - Mahony complementary filter for attitude estimation |
||
13 | http://www.x-io.co.uk |
||
14 | */ |
||
15 | |||
16 | |||
17 | #ifndef MPU6050_H_ |
||
18 | #define MPU6050_H_ |
||
19 | |||
20 | #include <avr/io.h> |
||
21 | #include "mpu6050registers.h" |
||
22 | |||
23 | #ifdef __cplusplus |
||
24 | extern "C" { |
||
25 | #endif |
||
26 | |||
27 | //i2c settings |
||
28 | #define MPU6050_I2CFLEURYPATH "i2cmaster.h" //define the path to i2c fleury lib |
||
29 | #define MPU6050_I2CINIT 0 //init i2c |
||
30 | |||
31 | //definitions |
||
32 | #define MPU6050_ADDR (0x68 <<1) //device address - 0x68 pin low (GND), 0x69 pin high (VCC) |
||
33 | |||
34 | //enable the getattitude functions |
||
35 | //because we do not have a magnetometer, we have to start the chip always in the same position |
||
36 | //then to obtain your object attitude you have to apply the aerospace sequence |
||
37 | //0 disabled |
||
38 | //1 mahony filter |
||
39 | //2 dmp chip processor |
||
40 | #define MPU6050_GETATTITUDE 2 |
||
41 | |||
42 | //definitions for raw data |
||
43 | //gyro and acc scale |
||
44 | #define MPU6050_GYRO_FS MPU6050_GYRO_FS_2000 |
||
45 | #define MPU6050_ACCEL_FS MPU6050_ACCEL_FS_2 |
||
46 | |||
47 | #define MPU6050_GYRO_LSB_250 131.0 |
||
48 | #define MPU6050_GYRO_LSB_500 65.5 |
||
49 | #define MPU6050_GYRO_LSB_1000 32.8 |
||
50 | #define MPU6050_GYRO_LSB_2000 16.4 |
||
51 | #if MPU6050_GYRO_FS == MPU6050_GYRO_FS_250 |
||
52 | #define MPU6050_GGAIN MPU6050_GYRO_LSB_250 |
||
53 | #elif MPU6050_GYRO_FS == MPU6050_GYRO_FS_500 |
||
54 | #define MPU6050_GGAIN MPU6050_GYRO_LSB_500 |
||
55 | #elif MPU6050_GYRO_FS == MPU6050_GYRO_FS_1000 |
||
56 | #define MPU6050_GGAIN MPU6050_GYRO_LSB_1000 |
||
57 | #elif MPU6050_GYRO_FS == MPU6050_GYRO_FS_2000 |
||
58 | #define MPU6050_GGAIN MPU6050_GYRO_LSB_2000 |
||
59 | #endif |
||
60 | |||
61 | #define MPU6050_ACCEL_LSB_2 16384.0 |
||
62 | #define MPU6050_ACCEL_LSB_4 8192.0 |
||
63 | #define MPU6050_ACCEL_LSB_8 4096.0 |
||
64 | #define MPU6050_ACCEL_LSB_16 2048.0 |
||
65 | #if MPU6050_ACCEL_FS == MPU6050_ACCEL_FS_2 |
||
66 | #define MPU6050_AGAIN MPU6050_ACCEL_LSB_2 |
||
67 | #elif MPU6050_ACCEL_FS == MPU6050_ACCEL_FS_4 |
||
68 | #define MPU6050_AGAIN MPU6050_ACCEL_LSB_4 |
||
69 | #elif MPU6050_ACCEL_FS == MPU6050_ACCEL_FS_8 |
||
70 | #define MPU6050_AGAIN MPU6050_ACCEL_LSB_8 |
||
71 | #elif MPU6050_ACCEL_FS == MPU6050_ACCEL_FS_16 |
||
72 | #define MPU6050_AGAIN MPU6050_ACCEL_LSB_16 |
||
73 | #endif |
||
74 | |||
75 | #define MPU6050_CALIBRATEDACCGYRO 1 //set to 1 if is calibrated |
||
76 | #if MPU6050_CALIBRATEDACCGYRO == 1 |
||
77 | #define MPU6050_AXOFFSET 0 |
||
78 | #define MPU6050_AYOFFSET 0 |
||
79 | #define MPU6050_AZOFFSET 0 |
||
80 | #define MPU6050_AXGAIN 16384.0 |
||
81 | #define MPU6050_AYGAIN 16384.0 |
||
82 | #define MPU6050_AZGAIN 16384.0 |
||
83 | #define MPU6050_GXOFFSET -42 |
||
84 | #define MPU6050_GYOFFSET 9 |
||
85 | #define MPU6050_GZOFFSET -29 |
||
86 | #define MPU6050_GXGAIN 16.4 |
||
87 | #define MPU6050_GYGAIN 16.4 |
||
88 | #define MPU6050_GZGAIN 16.4 |
||
89 | #endif |
||
90 | |||
91 | //definitions for attitude 1 function estimation |
||
92 | #if MPU6050_GETATTITUDE == 1 |
||
93 | #error "GETATTITUDE == 1 is not supported!" |
||
94 | //setup timer0 overflow event and define madgwickAHRSsampleFreq equal to timer0 frequency |
||
95 | //timerfreq = (FCPU / prescaler) / timerscale |
||
96 | // timerscale 8-bit = 256 |
||
97 | // es. 61 = (16000000 / 1024) / 256 |
||
98 | #define MPU6050_TIMER0INIT TCCR0B |=(1<<CS02)|(1<<CS00); TIMSK0 |=(1<<TOIE0); |
||
99 | #define mpu6050_mahonysampleFreq 61.0f // sample frequency in Hz |
||
100 | #define mpu6050_mahonytwoKpDef (2.0f * 0.5f) // 2 * proportional gain |
||
101 | #define mpu6050_mahonytwoKiDef (2.0f * 0.1f) // 2 * integral gain |
||
102 | #endif |
||
103 | |||
104 | |||
105 | #if MPU6050_GETATTITUDE == 2 |
||
106 | //dmp definitions |
||
107 | //packet size |
||
108 | #define MPU6050_DMP_dmpPacketSize 42 |
||
109 | //define INT0 rise edge interrupt |
||
110 | #define MPU6050_DMP_INT0SETUP EICRA |= (1<<ISC01) | (1<<ISC00) |
||
111 | //define enable and disable INT0 rise edge interrupt |
||
112 | #define MPU6050_DMP_INT0DISABLE EIMSK &= ~(1<<INT0) |
||
113 | #define MPU6050_DMP_INT0ENABLE EIMSK |= (1<<INT0) |
||
114 | extern volatile uint8_t mpu6050_mpuInterrupt; |
||
115 | #endif |
||
116 | |||
117 | //functions |
||
118 | extern void mpu6050_init(void); |
||
119 | extern uint8_t mpu6050_testConnection(void); |
||
120 | |||
121 | #if MPU6050_GETATTITUDE == 0 |
||
122 | extern void mpu6050_getRawData(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz); |
||
123 | extern void mpu6050_getConvData(double* axg, double* ayg, double* azg, double* gxds, double* gyds, double* gzds); |
||
124 | #endif |
||
125 | |||
126 | extern void mpu6050_setSleepDisabled(void); |
||
127 | extern void mpu6050_setSleepEnabled(void); |
||
128 | |||
129 | extern int8_t mpu6050_readBytes(uint8_t regAddr, uint8_t length, uint8_t *data); |
||
130 | extern int8_t mpu6050_readByte(uint8_t regAddr, uint8_t *data); |
||
131 | extern void mpu6050_writeBytes(uint8_t regAddr, uint8_t length, uint8_t* data); |
||
132 | extern void mpu6050_writeByte(uint8_t regAddr, uint8_t data); |
||
133 | extern int8_t mpu6050_readBits(uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t *data); |
||
134 | extern int8_t mpu6050_readBit(uint8_t regAddr, uint8_t bitNum, uint8_t *data); |
||
135 | extern void mpu6050_writeBits(uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data); |
||
136 | extern void mpu6050_writeBit(uint8_t regAddr, uint8_t bitNum, uint8_t data); |
||
137 | |||
138 | #if MPU6050_GETATTITUDE == 1 |
||
139 | extern void mpu6050_updateQuaternion(void); |
||
140 | extern void mpu6050_getQuaternion(double *qw, double *qx, double *qy, double *qz); |
||
141 | extern void mpu6050_getRollPitchYaw(double *pitch, double *roll, double *yaw); |
||
142 | #endif |
||
143 | |||
144 | #if MPU6050_GETATTITUDE == 2 |
||
145 | extern void mpu6050_writeWords(uint8_t regAddr, uint8_t length, uint16_t* data); |
||
146 | extern void mpu6050_setMemoryBank(uint8_t bank, uint8_t prefetchEnabled, uint8_t userBank); |
||
147 | extern void mpu6050_setMemoryStartAddress(uint8_t address); |
||
148 | extern void mpu6050_readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address); |
||
149 | extern uint8_t mpu6050_writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, uint8_t verify, uint8_t useProgMem); |
||
150 | extern uint8_t mpu6050_writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, uint8_t useProgMem); |
||
151 | extern uint16_t mpu6050_getFIFOCount(void); |
||
152 | extern void mpu6050_getFIFOBytes(uint8_t *data, uint8_t length); |
||
153 | extern uint8_t mpu6050_getIntStatus(void); |
||
154 | extern void mpu6050_resetFIFO(); |
||
155 | extern int8_t mpu6050_getXGyroOffset(void); |
||
156 | extern void mpu6050_setXGyroOffset(int8_t offset); |
||
157 | extern int8_t mpu6050_getYGyroOffset(void); |
||
158 | extern void mpu6050_setYGyroOffset(int8_t offset); |
||
159 | extern int8_t mpu6050_getZGyroOffset(void); |
||
160 | extern void mpu6050_setZGyroOffset(int8_t offset); |
||
161 | //base dmp |
||
162 | extern uint8_t mpu6050_dmpInitialize(void); |
||
163 | extern void mpu6050_dmpEnable(void); |
||
164 | extern void mpu6050_dmpDisable(void); |
||
165 | extern void mpu6050_getQuaternion(const uint8_t* packet, double *qw, double *qx, double *qy, double *qz); |
||
166 | extern void mpu6050_getRollPitchYaw(double qw, double qx, double qy, double qz, double *roll, double *pitch, double *yaw); |
||
167 | extern uint8_t mpu6050_getQuaternionWait(double *qw, double *qx, double *qy, double *qz); |
||
168 | #endif |
||
169 | |||
170 | #ifdef __cplusplus |
||
171 | } |
||
172 | #endif |
||
173 | |||
174 | #endif |