2 // Beware: this does not work on old Uno, requires a r3.
4 // I2C device class (I2Cdev) demonstration Arduino sketch for MPU6050 class using DMP (MotionApps v2.0)
5 // 6/21/2012 by Jeff Rowberg <jeff@rowberg.net>
6 // Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
9 // 2013-05-08 - added seamless Fastwire support
10 // - added note about gyro calibration
11 // 2012-06-21 - added note about Arduino 1.0.1 + Leonardo compatibility error
12 // 2012-06-20 - improved FIFO overflow handling and simplified read process
13 // 2012-06-19 - completely rearranged DMP initialization code and simplification
14 // 2012-06-13 - pull gyro and accel data from FIFO packet instead of reading directly
15 // 2012-06-09 - fix broken FIFO read sequence and change interrupt detection to RISING
16 // 2012-06-05 - add gravity-compensated initial reference frame acceleration output
17 // - add 3D math helper file to DMP6 example sketch
18 // - add Euler output and Yaw/Pitch/Roll output formats
19 // 2012-06-04 - remove accel offset clearing for better results (thanks Sungon Lee)
20 // 2012-06-01 - fixed gyro sensitivity to be 2000 deg/sec instead of 250
21 // 2012-05-30 - basic DMP initialization working
23 /* ============================================
24 I2Cdev device library code is placed under the MIT license
25 Copyright (c) 2012 Jeff Rowberg
27 Permission is hereby granted, free of charge, to any person obtaining a copy
28 of this software and associated documentation files (the "Software"), to deal
29 in the Software without restriction, including without limitation the rights
30 to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
31 copies of the Software, and to permit persons to whom the Software is
32 furnished to do so, subject to the following conditions:
34 The above copyright notice and this permission notice shall be included in
35 all copies or substantial portions of the Software.
37 THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
38 IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
39 FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
40 AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
41 LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
42 OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
44 ===============================================
47 // I2Cdev and MPU6050 must be installed as libraries, or else the .cpp/.h files
48 // for both classes must be in the include path of your project
51 #include "MPU6050_6Axis_MotionApps20.h"
52 //#include "MPU6050.h" // not necessary if using MotionApps include file
54 // Arduino Wire library is required if I2Cdev I2CDEV_ARDUINO_WIRE implementation
55 // is used in I2Cdev.h
56 #if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE
60 // class default I2C address is 0x68
61 // specific I2C addresses may be passed as a parameter here
62 // AD0 low = 0x68 (default for SparkFun breakout and InvenSense evaluation board)
65 //MPU6050 mpu(0x69); // <-- use for AD0 high
67 /* =========================================================================
68 NOTE: In addition to connection 3.3v, GND, SDA, and SCL, this sketch
69 depends on the MPU-6050's INT pin being connected to the Arduino's
70 external interrupt #0 pin. On the Arduino Uno and Mega 2560, this is
72 * ========================================================================= */
74 /* =========================================================================
75 NOTE: Arduino v1.0.1 with the Leonardo board generates a compile error
76 when using Serial.write(buf, len). The Teapot output uses this method.
77 The solution requires a modification to the Arduino USBAPI.h file, which
78 is fortunately simple, but annoying. This will be fixed in the next IDE
79 release. For more info, see these links:
81 http://arduino.cc/forum/index.php/topic,109987.0.html
82 http://code.google.com/p/arduino/issues/detail?id=958
83 * ========================================================================= */
87 // uncomment "OUTPUT_READABLE_QUATERNION" if you want to see the actual
88 // quaternion components in a [w, x, y, z] format (not best for parsing
89 // on a remote host such as Processing or something though)
90 //#define OUTPUT_READABLE_QUATERNION
92 // uncomment "OUTPUT_READABLE_EULER" if you want to see Euler angles
93 // (in degrees) calculated from the quaternions coming from the FIFO.
94 // Note that Euler angles suffer from gimbal lock (for more info, see
95 // http://en.wikipedia.org/wiki/Gimbal_lock)
96 //#define OUTPUT_READABLE_EULER
98 // uncomment "OUTPUT_READABLE_YAWPITCHROLL" if you want to see the yaw/
99 // pitch/roll angles (in degrees) calculated from the quaternions coming
100 // from the FIFO. Note this also requires gravity vector calculations.
101 // Also note that yaw/pitch/roll angles suffer from gimbal lock (for
102 // more info, see: http://en.wikipedia.org/wiki/Gimbal_lock)
103 #define OUTPUT_READABLE_YAWPITCHROLL
105 // uncomment "OUTPUT_READABLE_REALACCEL" if you want to see acceleration
106 // components with gravity removed. This acceleration reference frame is
107 // not compensated for orientation, so +X is always +X according to the
108 // sensor, just without the effects of gravity. If you want acceleration
109 // compensated for orientation, us OUTPUT_READABLE_WORLDACCEL instead.
110 //#define OUTPUT_READABLE_REALACCEL
112 // uncomment "OUTPUT_READABLE_WORLDACCEL" if you want to see acceleration
113 // components with gravity removed and adjusted for the world frame of
114 // reference (yaw is relative to initial orientation, since no magnetometer
115 // is present in this case). Could be quite handy in some cases.
116 //#define OUTPUT_READABLE_WORLDACCEL
118 // uncomment "OUTPUT_TEAPOT" if you want output that matches the
119 // format used for the InvenSense teapot demo
120 //#define OUTPUT_TEAPOT
124 #define LED_PIN 13 // (Arduino is 13, Teensy is 11, Teensy++ is 6)
125 bool blinkState = false;
127 // MPU control/status vars
128 bool dmpReady = false; // set true if DMP init was successful
129 uint8_t mpuIntStatus; // holds actual interrupt status byte from MPU
130 uint8_t devStatus; // return status after each device operation (0 = success, !0 = error)
131 uint16_t packetSize; // expected DMP packet size (default is 42 bytes)
132 uint16_t fifoCount; // count of all bytes currently in FIFO
133 uint8_t fifoBuffer[64]; // FIFO storage buffer
135 // orientation/motion vars
136 Quaternion q; // [w, x, y, z] quaternion container
137 VectorInt16 aa; // [x, y, z] accel sensor measurements
138 VectorInt16 aaReal; // [x, y, z] gravity-free accel sensor measurements
139 VectorInt16 aaWorld; // [x, y, z] world-frame accel sensor measurements
140 VectorFloat gravity; // [x, y, z] gravity vector
141 float euler[3]; // [psi, theta, phi] Euler angle container
142 float ypr[3]; // [yaw, pitch, roll] yaw/pitch/roll container and gravity vector
144 // packet structure for InvenSense teapot demo
145 uint8_t teapotPacket[14] = { '$', 0x02, 0,0, 0,0, 0,0, 0,0, 0x00, 0x00, '\r', '\n' };
149 // ================================================================
150 // === INTERRUPT DETECTION ROUTINE ===
151 // ================================================================
153 volatile bool mpuInterrupt = false; // indicates whether MPU interrupt pin has gone high
154 void dmpDataReady() {
160 // ================================================================
161 // === INITIAL SETUP ===
162 // ================================================================
165 // join I2C bus (I2Cdev library doesn't do this automatically)
166 #if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE
168 TWBR = 24; // 400kHz I2C clock (200kHz if CPU is 8MHz)
169 #elif I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE
170 Fastwire::setup(400, true);
173 // initialize serial communication
174 // (115200 chosen because it is required for Teapot Demo output, but it's
175 // really up to you depending on your project)
176 Serial.begin(115200);
177 while (!Serial); // wait for Leonardo enumeration, others continue immediately
179 // NOTE: 8MHz or slower host processors, like the Teensy @ 3.3v or Ardunio
180 // Pro Mini running at 3.3v, cannot handle this baud rate reliably due to
181 // the baud timing being too misaligned with processor ticks. You must use
182 // 38400 or slower in these cases, or use some kind of external separate
183 // crystal solution for the UART timer.
186 Serial.println(F("Initializing I2C devices..."));
190 Serial.println(F("Testing device connections..."));
191 Serial.println(mpu.testConnection() ? F("MPU6050 connection successful") : F("MPU6050 connection failed"));
194 Serial.println(F("\nSend any character to begin DMP programming and demo: "));
195 while (Serial.available() && Serial.read()); // empty buffer
196 while (!Serial.available()); // wait for data
197 while (Serial.available() && Serial.read()); // empty buffer again
199 // load and configure the DMP
200 Serial.println(F("Initializing DMP..."));
201 devStatus = mpu.dmpInitialize();
203 // supply your own gyro offsets here, scaled for min sensitivity
204 mpu.setXGyroOffset(220);
205 mpu.setYGyroOffset(76);
206 mpu.setZGyroOffset(-85);
207 mpu.setZAccelOffset(1788); // 1688 factory default for my test chip
209 // make sure it worked (returns 0 if so)
210 if (devStatus == 0) {
211 // turn on the DMP, now that it's ready
212 Serial.println(F("Enabling DMP..."));
213 mpu.setDMPEnabled(true);
215 // enable Arduino interrupt detection
216 Serial.println(F("Enabling interrupt detection (Arduino external interrupt 0)..."));
217 attachInterrupt(0, dmpDataReady, RISING);
218 mpuIntStatus = mpu.getIntStatus();
220 // set our DMP Ready flag so the main loop() function knows it's okay to use it
221 Serial.println(F("DMP ready! Waiting for first interrupt..."));
224 // get expected DMP packet size for later comparison
225 packetSize = mpu.dmpGetFIFOPacketSize();
228 // 1 = initial memory load failed
229 // 2 = DMP configuration updates failed
230 // (if it's going to break, usually the code will be 1)
231 Serial.print(F("DMP Initialization failed (code "));
232 Serial.print(devStatus);
233 Serial.println(F(")"));
236 // configure LED for output
237 pinMode(LED_PIN, OUTPUT);
242 // ================================================================
243 // === MAIN PROGRAM LOOP ===
244 // ================================================================
247 // if programming failed, don't try to do anything
248 if (!dmpReady) return;
250 // wait for MPU interrupt or extra packet(s) available
251 while (!mpuInterrupt && fifoCount < packetSize) {
252 // other program behavior stuff here
256 // if you are really paranoid you can frequently test in between other
257 // stuff to see if mpuInterrupt is true, and if so, "break;" from the
258 // while() loop to immediately process the MPU data
264 // reset interrupt flag and get INT_STATUS byte
265 mpuInterrupt = false;
266 mpuIntStatus = mpu.getIntStatus();
268 // get current FIFO count
269 fifoCount = mpu.getFIFOCount();
271 // check for overflow (this should never happen unless our code is too inefficient)
272 if ((mpuIntStatus & 0x10) || fifoCount == 1024) {
273 // reset so we can continue cleanly
275 Serial.println(F("FIFO overflow!"));
277 // otherwise, check for DMP data ready interrupt (this should happen frequently)
278 } else if (mpuIntStatus & 0x02) {
279 // wait for correct available data length, should be a VERY short wait
280 while (fifoCount < packetSize) fifoCount = mpu.getFIFOCount();
282 // read a packet from FIFO
283 mpu.getFIFOBytes(fifoBuffer, packetSize);
285 // track FIFO count here in case there is > 1 packet available
286 // (this lets us immediately read more without waiting for an interrupt)
287 fifoCount -= packetSize;
289 #ifdef OUTPUT_READABLE_QUATERNION
290 // display quaternion values in easy matrix form: w x y z
291 mpu.dmpGetQuaternion(&q, fifoBuffer);
292 Serial.print("quat\t");
302 #ifdef OUTPUT_READABLE_EULER
303 // display Euler angles in degrees
304 mpu.dmpGetQuaternion(&q, fifoBuffer);
305 mpu.dmpGetEuler(euler, &q);
306 Serial.print("euler\t");
307 Serial.print(euler[0] * 180/M_PI);
309 Serial.print(euler[1] * 180/M_PI);
311 Serial.println(euler[2] * 180/M_PI);
314 #ifdef OUTPUT_READABLE_YAWPITCHROLL
315 // display Euler angles in degrees
316 mpu.dmpGetQuaternion(&q, fifoBuffer);
317 mpu.dmpGetGravity(&gravity, &q);
318 mpu.dmpGetYawPitchRoll(ypr, &q, &gravity);
319 Serial.print("ypr\t");
320 Serial.print(ypr[0] * 180/M_PI);
322 Serial.print(ypr[1] * 180/M_PI);
324 Serial.println(ypr[2] * 180/M_PI);
327 #ifdef OUTPUT_READABLE_REALACCEL
328 // display real acceleration, adjusted to remove gravity
329 mpu.dmpGetQuaternion(&q, fifoBuffer);
330 mpu.dmpGetAccel(&aa, fifoBuffer);
331 mpu.dmpGetGravity(&gravity, &q);
332 mpu.dmpGetLinearAccel(&aaReal, &aa, &gravity);
333 Serial.print("areal\t");
334 Serial.print(aaReal.x);
336 Serial.print(aaReal.y);
338 Serial.println(aaReal.z);
341 #ifdef OUTPUT_READABLE_WORLDACCEL
342 // display initial world-frame acceleration, adjusted to remove gravity
343 // and rotated based on known orientation from quaternion
344 mpu.dmpGetQuaternion(&q, fifoBuffer);
345 mpu.dmpGetAccel(&aa, fifoBuffer);
346 mpu.dmpGetGravity(&gravity, &q);
347 mpu.dmpGetLinearAccel(&aaReal, &aa, &gravity);
348 mpu.dmpGetLinearAccelInWorld(&aaWorld, &aaReal, &q);
349 Serial.print("aworld\t");
350 Serial.print(aaWorld.x);
352 Serial.print(aaWorld.y);
354 Serial.println(aaWorld.z);
358 // display quaternion values in InvenSense Teapot demo format:
359 teapotPacket[2] = fifoBuffer[0];
360 teapotPacket[3] = fifoBuffer[1];
361 teapotPacket[4] = fifoBuffer[4];
362 teapotPacket[5] = fifoBuffer[5];
363 teapotPacket[6] = fifoBuffer[8];
364 teapotPacket[7] = fifoBuffer[9];
365 teapotPacket[8] = fifoBuffer[12];
366 teapotPacket[9] = fifoBuffer[13];
367 Serial.write(teapotPacket, 14);
368 teapotPacket[11]++; // packetCount, loops at 0xFF on purpose
371 // blink LED to indicate activity
372 blinkState = !blinkState;
373 digitalWrite(LED_PIN, blinkState);