MPU9150Lib.h
Go to the documentation of this file.
00001 
00002 //
00003 //  This file is part of MPU9150Lib
00004 //
00005 //  Copyright (c) 2013 Pansenti, LLC
00006 //
00007 //  Permission is hereby granted, free of charge, to any person obtaining a copy of 
00008 //  this software and associated documentation files (the "Software"), to deal in 
00009 //  the Software without restriction, including without limitation the rights to use, 
00010 //  copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the 
00011 //  Software, and to permit persons to whom the Software is furnished to do so, 
00012 //  subject to the following conditions:
00013 //
00014 //  The above copyright notice and this permission notice shall be included in all 
00015 //  copies or substantial portions of the Software.
00016 //
00017 //  THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, 
00018 //  INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 
00019 //  PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT 
00020 //  HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION 
00021 //  OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE 
00022 //  SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
00023 
00024 #ifndef _MPU9150LIB_H_
00025 #define _MPU9150LIB_H_
00026 
00027 #include <Arduino.h>
00028 #include "MPUQuaternion.h"
00029 #include "CalLib.h"
00030 
00031 //  Define this symbol to get debug info
00032 
00033 //#define MPULIB_DEBUG
00034 
00035 //  This symbol defines the scaled range for mag and accel values
00036 
00037 #define SENSOR_RANGE   4096
00038 
00039 class MPU9150Lib
00040 {
00041 public: 
00042 
00043   // Constructor
00044 
00045   MPU9150Lib();
00046 
00047   // selectDevice() can be called to select a device:
00048   //
00049   //   0 = device at address 0x68 (default)
00050   //   1 = device at address 0x69
00051   //
00052   // selectDevice() must be called before init()
00053 
00054   void selectDevice(int device);
00055 
00056   // these two functions control if calibration data is used. Must be called before init()
00057   // if defaults (use mag and accel cal) aren't required.
00058 
00059   void useAccelCal(boolean useCal);
00060   void useMagCal(boolean useCal);
00061 
00062   // init must be called to setup the MPU chip.
00063   // mpuRate is the update rate in Hz.
00064   // magMix controls the amoutn of influence that the magnetometer has on yaw:
00065   //   0 = just use MPU gyros (will not be referenced to north)
00066   //   1 = just use magnetometer with no input from gyros
00067   //   2-n = mix the two. Higher numbers decrease correction from magnetometer
00068   // It returns false if something went wrong with the initialization.
00069   // magRate is the magnetometer update rate in Hz. magRate <= mpuRate.
00070   //   Also, magRate must be <= 100Hz.
00071   // lpf is the low pass filter setting - can be between 5Hz and 188Hz.
00072   //   0 means let the MotionDriver library decide.
00073     
00074   boolean init(int mpuRate, int magMix = 5, int magRate = 10, int lpf = 0);
00075   
00076   //  read checks to see if there's been a new update.
00077   //  returns true if yes, false if not.
00078   
00079   boolean read();
00080 
00081   // disableAccelCal can be called while running to disable
00082   // accel bias offsets while performing accel calibration
00083 
00084   void disableAccelCal();
00085 
00086   //  check if calibration in use
00087   
00088   boolean isMagCal();
00089   boolean isAccelCal();
00090 
00091   //  these functions can be used to display quaternions and vectors
00092   
00093   void printQuaternion(long *quaternion);
00094   void printQuaternion(float *quaternion);
00095   void printVector(short *vec);
00096   void printVector(float *vec);
00097   void printAngles(float *vec);
00098   
00099   //  these variables are the values from the MPU
00100   
00101   long m_rawQuaternion[4];                                  // the quaternion output from the DMP
00102   short m_rawGyro[3];                                       // calibrated gyro output from the sensor
00103   short m_rawAccel[3];                                      // raw accel data
00104   short m_rawMag[3];                                        // raw mag data 
00105   
00106   //  these variables are processed results
00107   
00108   float m_dmpQuaternion[4];                                 // float and normalized version of the dmp quaternion
00109   float m_dmpEulerPose[3];                                  // Euler angles from the DMP quaternion
00110   short m_calAccel[3];                                      // calibrated and scaled accel data
00111   short m_calMag[3];                                        // calibrated mag data
00112 
00113   // these variables are the fused results
00114 
00115   float m_fusedEulerPose[3];                                // the fused Euler angles
00116   float m_fusedQuaternion[4];                                                           // the fused quaternion
00117 
00118 private:
00119   CALLIB_DATA m_calData;                                    // calibration data
00120   boolean m_useMagCalibration;                              // true if use mag calibration
00121   boolean m_useAccelCalibration;                            // true if use mag calibration
00122   byte m_device;                                            // IMU device index
00123   int m_magMix;                                             // controls gyro and magnetometer mixing for yaw
00124   unsigned long m_magInterval;                              // interval between mag reads in mS
00125   unsigned long m_lastMagSample;                            // last time mag was read
00126 
00127   void dataFusion();                                        // fuse mag data with the dmp quaternion
00128 
00129   float m_lastDMPYaw;                                       // the last yaw from the DMP gyros
00130   float m_lastYaw;                                          // last calculated output yaw
00131 
00132   //  calibration data in processed form
00133 
00134   short m_magXOffset;                                                                           // offset to be structed for mag X
00135   short m_magXRange;                                                                            // range of mag X
00136   short m_magYOffset;                                                                           // offset to be structed for mag Y
00137   short m_magYRange;                                                                            // range of mag Y
00138   short m_magZOffset;                                                                           // offset to be structed for mag Z
00139   short m_magZRange;                                                                            // range of mag Z
00140 
00141   short m_accelXRange;                                                                          // range of accel X
00142   short m_accelYRange;                                                                          // range of accel Y
00143   short m_accelZRange;                                                                          // range of accel Z
00144   long m_accelOffset[3];                                    // offsets for accel
00145 
00146 };
00147 
00148 #endif // _MPU9150LIB_H_


ric_mc
Author(s): RoboTiCan
autogenerated on Thu Aug 27 2015 14:39:49