inv_mpu.h
Go to the documentation of this file.
00001 /*
00002  $License:
00003     Copyright (C) 2011-2012 InvenSense Corporation, All Rights Reserved.
00004     See included License.txt for License information.
00005  $
00006  */
00021 #ifndef _INV_MPU_H_
00022 #define _INV_MPU_H_
00023 
00024 #include "I2Cdev.h"
00025 
00026 //  Define this symbol to get debug messages
00027 
00028 #define  MPU_DEBUG
00029 
00030 //  Define this symbol to enable rarely-used functions from library
00031 
00032 //#define MPU_MAXIMAL
00033 
00034 //  This symbol defines how many devices are supported
00035 
00036 #define MPU_MAX_DEVICES 2
00037 
00038 //  Call this function before using the MPU to select the correct device
00039 
00040 int mpu_select_device(int device);
00041 
00042 inline void get_ms(long unsigned int *timestamp)
00043 {
00044     *timestamp = millis(); 
00045 }
00046 
00047 //  IMU hardware device defines
00048 
00049 #define MPU9150
00050 
00051 #define INV_X_GYRO      (0x40)
00052 #define INV_Y_GYRO      (0x20)
00053 #define INV_Z_GYRO      (0x10)
00054 #define INV_XYZ_GYRO    (INV_X_GYRO | INV_Y_GYRO | INV_Z_GYRO)
00055 #define INV_XYZ_ACCEL   (0x08)
00056 #define INV_XYZ_COMPASS (0x01)
00057 
00058 struct int_param_s {
00059     void (*cb)(void);
00060     unsigned short pin;
00061     unsigned char lp_exit;
00062     unsigned char active_low;
00063 };
00064 
00065 #define MPU_INT_STATUS_DATA_READY       (0x0001)
00066 #define MPU_INT_STATUS_DMP              (0x0002)
00067 #define MPU_INT_STATUS_PLL_READY        (0x0004)
00068 #define MPU_INT_STATUS_I2C_MST          (0x0008)
00069 #define MPU_INT_STATUS_FIFO_OVERFLOW    (0x0010)
00070 #define MPU_INT_STATUS_ZMOT             (0x0020)
00071 #define MPU_INT_STATUS_MOT              (0x0040)
00072 #define MPU_INT_STATUS_FREE_FALL        (0x0080)
00073 #define MPU_INT_STATUS_DMP_0            (0x0100)
00074 #define MPU_INT_STATUS_DMP_1            (0x0200)
00075 #define MPU_INT_STATUS_DMP_2            (0x0400)
00076 #define MPU_INT_STATUS_DMP_3            (0x0800)
00077 #define MPU_INT_STATUS_DMP_4            (0x1000)
00078 #define MPU_INT_STATUS_DMP_5            (0x2000)
00079 
00080 /* Set up APIs */
00081 void mpu_init_structures();
00082 
00083 int mpu_init(struct int_param_s *int_param);
00084 int mpu_init_slave(void);
00085 int mpu_set_bypass(unsigned char bypass_on);
00086 
00087 /* Configuration APIs */
00088 int mpu_lp_accel_mode(unsigned char rate);
00089 int mpu_lp_motion_interrupt(unsigned short thresh, unsigned char time,
00090     unsigned char lpa_freq);
00091 int mpu_set_int_level(unsigned char active_low);
00092 int mpu_set_int_latched(unsigned char enable);
00093 
00094 int mpu_set_dmp_state(unsigned char enable);
00095 int mpu_get_dmp_state(unsigned char *enabled);
00096 
00097 int mpu_get_lpf(unsigned short *lpf);
00098 int mpu_set_lpf(unsigned short lpf);
00099 
00100 int mpu_get_gyro_fsr(unsigned short *fsr);
00101 int mpu_set_gyro_fsr(unsigned short fsr);
00102 
00103 int mpu_get_accel_fsr(unsigned char *fsr);
00104 int mpu_set_accel_fsr(unsigned char fsr);
00105 
00106 int mpu_get_compass_fsr(unsigned short *fsr);
00107 
00108 int mpu_get_gyro_sens(float *sens);
00109 int mpu_get_accel_sens(unsigned short *sens);
00110 
00111 int mpu_get_sample_rate(unsigned short *rate);
00112 int mpu_set_sample_rate(unsigned short rate);
00113 int mpu_get_compass_sample_rate(unsigned short *rate);
00114 int mpu_set_compass_sample_rate(unsigned short rate);
00115 
00116 int mpu_get_fifo_config(unsigned char *sensors);
00117 int mpu_configure_fifo(unsigned char sensors);
00118 
00119 int mpu_get_power_state(unsigned char *power_on);
00120 int mpu_set_sensors(unsigned char sensors);
00121 
00122 int mpu_set_accel_bias(const long *accel_bias);
00123 
00124 /* Data getter/setter APIs */
00125 int mpu_get_gyro_reg(short *data, unsigned long *timestamp);
00126 int mpu_get_accel_reg(short *data, unsigned long *timestamp);
00127 int mpu_get_compass_reg(short *data, unsigned long *timestamp);
00128 int mpu_get_temperature(long *data, unsigned long *timestamp);
00129 
00130 int mpu_get_int_status(short *status);
00131 int mpu_read_fifo(short *gyro, short *accel, unsigned long *timestamp,
00132     unsigned char *sensors, unsigned char *more);
00133 int mpu_read_fifo_stream(unsigned short length, unsigned char *data,
00134     unsigned char *more);
00135 int mpu_reset_fifo(void);
00136 
00137 int mpu_write_mem(unsigned short mem_addr, unsigned short length,
00138     unsigned char *data);
00139 int mpu_read_mem(unsigned short mem_addr, unsigned short length,
00140     unsigned char *data);
00141 int mpu_load_firmware(unsigned short length, const unsigned char *firmware,
00142     unsigned short start_addr, unsigned short sample_rate);
00143 
00144 int mpu_reg_dump(void);
00145 int mpu_read_reg(unsigned char reg, unsigned char *data);
00146 
00147 #ifdef MPU_MAXIMAL
00148 int mpu_run_self_test(long *gyro, long *accel);
00149 int mpu_register_tap_cb(void (*func)(unsigned char, unsigned char));
00150 #endif // MPU_MAXIMAL
00151 
00152 #endif  /* #ifndef _INV_MPU_H_ */
00153 


segbot_firmware
Author(s): Jose Bigio, Jack O'Quin, Tim Eckel (NewPing library)
autogenerated on Thu Jun 6 2019 21:37:01