An I2C-based driver for Invensense gyroscopes. More...
#include "I2Cdev.h"
Go to the source code of this file.
Classes | |
struct | int_param_s |
Defines | |
#define | INV_X_GYRO (0x40) |
#define | INV_XYZ_ACCEL (0x08) |
#define | INV_XYZ_COMPASS (0x01) |
#define | INV_XYZ_GYRO (INV_X_GYRO | INV_Y_GYRO | INV_Z_GYRO) |
#define | INV_Y_GYRO (0x20) |
#define | INV_Z_GYRO (0x10) |
#define | MPU9150 |
#define | MPU_INT_STATUS_DATA_READY (0x0001) |
#define | MPU_INT_STATUS_DMP (0x0002) |
#define | MPU_INT_STATUS_DMP_0 (0x0100) |
#define | MPU_INT_STATUS_DMP_1 (0x0200) |
#define | MPU_INT_STATUS_DMP_2 (0x0400) |
#define | MPU_INT_STATUS_DMP_3 (0x0800) |
#define | MPU_INT_STATUS_DMP_4 (0x1000) |
#define | MPU_INT_STATUS_DMP_5 (0x2000) |
#define | MPU_INT_STATUS_FIFO_OVERFLOW (0x0010) |
#define | MPU_INT_STATUS_FREE_FALL (0x0080) |
#define | MPU_INT_STATUS_I2C_MST (0x0008) |
#define | MPU_INT_STATUS_MOT (0x0040) |
#define | MPU_INT_STATUS_PLL_READY (0x0004) |
#define | MPU_INT_STATUS_ZMOT (0x0020) |
#define | MPU_MAX_DEVICES 2 |
Functions | |
void | get_ms (long unsigned int *timestamp) |
int | mpu_configure_fifo (unsigned char sensors) |
Select which sensors are pushed to FIFO. sensors can contain a combination of the following flags: INV_X_GYRO, INV_Y_GYRO, INV_Z_GYRO INV_XYZ_GYRO INV_XYZ_ACCEL. | |
int | mpu_get_accel_fsr (unsigned char *fsr) |
Get the accel full-scale range. | |
int | mpu_get_accel_reg (short *data, unsigned long *timestamp) |
Read raw accel data directly from the registers. | |
int | mpu_get_accel_sens (unsigned short *sens) |
Get accel sensitivity scale factor. | |
int | mpu_get_compass_fsr (unsigned short *fsr) |
Get the compass full-scale range. | |
int | mpu_get_compass_reg (short *data, unsigned long *timestamp) |
Read raw compass data. | |
int | mpu_get_compass_sample_rate (unsigned short *rate) |
Get compass sampling rate. | |
int | mpu_get_dmp_state (unsigned char *enabled) |
Get DMP state. | |
int | mpu_get_fifo_config (unsigned char *sensors) |
Get current FIFO configuration. sensors can contain a combination of the following flags: INV_X_GYRO, INV_Y_GYRO, INV_Z_GYRO INV_XYZ_GYRO INV_XYZ_ACCEL. | |
int | mpu_get_gyro_fsr (unsigned short *fsr) |
Get the gyro full-scale range. | |
int | mpu_get_gyro_reg (short *data, unsigned long *timestamp) |
Read raw gyro data directly from the registers. | |
int | mpu_get_gyro_sens (float *sens) |
Get gyro sensitivity scale factor. | |
int | mpu_get_int_status (short *status) |
Read the MPU interrupt status registers. | |
int | mpu_get_lpf (unsigned short *lpf) |
Get the current DLPF setting. | |
int | mpu_get_power_state (unsigned char *power_on) |
Get current power state. | |
int | mpu_get_sample_rate (unsigned short *rate) |
Get sampling rate. | |
int | mpu_get_temperature (long *data, unsigned long *timestamp) |
Read temperature data directly from the registers. | |
int | mpu_init (struct int_param_s *int_param) |
Initialize hardware. Initial configuration: Gyro FSR: +/- 2000DPS Accel FSR +/- 2G DLPF: 42Hz FIFO rate: 50Hz Clock source: Gyro PLL FIFO: Disabled. Data ready interrupt: Disabled, active low, unlatched. | |
int | mpu_init_slave (void) |
void | mpu_init_structures () |
int | mpu_load_firmware (unsigned short length, const unsigned char *firmware, unsigned short start_addr, unsigned short sample_rate) |
Load and verify DMP image. | |
int | mpu_lp_accel_mode (unsigned char rate) |
Enter low-power accel-only mode. In low-power accel mode, the chip goes to sleep and only wakes up to sample the accelerometer at one of the following frequencies: MPU6050: 1.25Hz, 5Hz, 20Hz, 40Hz MPU6500: 1.25Hz, 2.5Hz, 5Hz, 10Hz, 20Hz, 40Hz, 80Hz, 160Hz, 320Hz, 640Hz If the requested rate is not one listed above, the device will be set to the next highest rate. Requesting a rate above the maximum supported frequency will result in an error. To select a fractional wake-up frequency, round down the value passed to rate. | |
int | mpu_lp_motion_interrupt (unsigned short thresh, unsigned char time, unsigned char lpa_freq) |
Enters LP accel motion interrupt mode. The behavior of this feature is very different between the MPU6050 and the MPU6500. Each chip's version of this feature is explained below. | |
int | mpu_read_fifo (short *gyro, short *accel, unsigned long *timestamp, unsigned char *sensors, unsigned char *more) |
Get one packet from the FIFO. If sensors does not contain a particular sensor, disregard the data returned to that pointer. sensors can contain a combination of the following flags: INV_X_GYRO, INV_Y_GYRO, INV_Z_GYRO INV_XYZ_GYRO INV_XYZ_ACCEL If the FIFO has no new data, sensors will be zero. If the FIFO is disabled, sensors will be zero and this function will return a non-zero error code. | |
int | mpu_read_fifo_stream (unsigned short length, unsigned char *data, unsigned char *more) |
Get one unparsed packet from the FIFO. This function should be used if the packet is to be parsed elsewhere. | |
int | mpu_read_mem (unsigned short mem_addr, unsigned short length, unsigned char *data) |
Read from the DMP memory. This function prevents I2C reads past the bank boundaries. The DMP memory is only accessible when the chip is awake. | |
int | mpu_read_reg (unsigned char reg, unsigned char *data) |
Read from a single register. NOTE: The memory and FIFO read/write registers cannot be accessed. | |
int | mpu_reg_dump (void) |
Register dump for testing. | |
int | mpu_reset_fifo (void) |
Reset FIFO read/write pointers. | |
int | mpu_select_device (int device) |
int | mpu_set_accel_bias (const long *accel_bias) |
Push biases to the accel bias registers. This function expects biases relative to the current sensor output, and these biases will be added to the factory-supplied values. | |
int | mpu_set_accel_fsr (unsigned char fsr) |
Set the accel full-scale range. | |
int | mpu_set_bypass (unsigned char bypass_on) |
Set device to bypass mode. | |
int | mpu_set_compass_sample_rate (unsigned short rate) |
Set compass sampling rate. The compass on the auxiliary I2C bus is read by the MPU hardware at a maximum of 100Hz. The actual rate can be set to a fraction of the gyro sampling rate. | |
int | mpu_set_dmp_state (unsigned char enable) |
Enable/disable DMP support. | |
int | mpu_set_gyro_fsr (unsigned short fsr) |
Set the gyro full-scale range. | |
int | mpu_set_int_latched (unsigned char enable) |
Enable latched interrupts. Any MPU register will clear the interrupt. | |
int | mpu_set_int_level (unsigned char active_low) |
Set interrupt level. | |
int | mpu_set_lpf (unsigned short lpf) |
Set digital low pass filter. The following LPF settings are supported: 188, 98, 42, 20, 10, 5. | |
int | mpu_set_sample_rate (unsigned short rate) |
Set sampling rate. Sampling rate must be between 4Hz and 1kHz. | |
int | mpu_set_sensors (unsigned char sensors) |
Turn specific sensors on/off. sensors can contain a combination of the following flags: INV_X_GYRO, INV_Y_GYRO, INV_Z_GYRO INV_XYZ_GYRO INV_XYZ_ACCEL INV_XYZ_COMPASS. | |
int | mpu_write_mem (unsigned short mem_addr, unsigned short length, unsigned char *data) |
Write to the DMP memory. This function prevents I2C writes past the bank boundaries. The DMP memory is only accessible when the chip is awake. |
An I2C-based driver for Invensense gyroscopes.
This driver currently works for the following devices: MPU6050 MPU6500 MPU9150 (or MPU6050 w/ AK8975 on the auxiliary bus) MPU9250 (or MPU6500 w/ AK8963 on the auxiliary bus)
Definition in file inv_mpu.h.