Classes | Defines | Enumerations | Functions | Variables
inv_mpu.cpp File Reference
#include <stdio.h>
#include <stdint.h>
#include <stdlib.h>
#include <string.h>
#include <math.h>
#include "inv_mpu.h"
Include dependency graph for inv_mpu.cpp:

Go to the source code of this file.

Classes

struct  chip_cfg_s
struct  gyro_reg_s
struct  gyro_state_s
struct  hw_s
struct  motion_int_cache_s
struct  test_s

Defines

#define AK8975_SECONDARY
#define AK89xx_FSR   (9830)
#define AK89xx_SECONDARY
#define AKM_BIT_SELF_TEST   (0x40)
#define AKM_DATA_ERROR   (0x40)
#define AKM_DATA_OVERRUN   (0x02)
#define AKM_DATA_READY   (0x01)
#define AKM_FUSE_ROM_ACCESS   (0x0F | SUPPORTS_AK89xx_HIGH_SENS)
#define AKM_MODE_SELF_TEST   (0x08 | SUPPORTS_AK89xx_HIGH_SENS)
#define AKM_OVERFLOW   (0x80)
#define AKM_POWER_DOWN   (0x00 | SUPPORTS_AK89xx_HIGH_SENS)
#define AKM_REG_ASAX   (0x10)
#define AKM_REG_ASAY   (0x11)
#define AKM_REG_ASAZ   (0x12)
#define AKM_REG_ASTC   (0x0C)
#define AKM_REG_CNTL   (0x0A)
#define AKM_REG_HXL   (0x03)
#define AKM_REG_ST1   (0x02)
#define AKM_REG_ST2   (0x09)
#define AKM_REG_WHOAMI   (0x00)
#define AKM_SINGLE_MEASUREMENT   (0x01 | SUPPORTS_AK89xx_HIGH_SENS)
#define AKM_WHOAMI   (0x48)
#define BIT_ACTL   (0x80)
#define BIT_ANY_RD_CLR   (0x10)
#define BIT_AUX_IF_EN   (0x20)
#define BIT_BYPASS_EN   (0x02)
#define BIT_DATA_RDY_EN   (0x01)
#define BIT_DMP_EN   (0x80)
#define BIT_DMP_INT_EN   (0x02)
#define BIT_DMP_RST   (0x08)
#define BIT_FIFO_EN   (0x40)
#define BIT_FIFO_OVERFLOW   (0x10)
#define BIT_FIFO_RST   (0x04)
#define BIT_FIFO_SIZE_1024   (0x40)
#define BIT_FIFO_SIZE_2048   (0x80)
#define BIT_FIFO_SIZE_4096   (0xC0)
#define BIT_I2C_MST_VDDIO   (0x80)
#define BIT_I2C_READ   (0x80)
#define BIT_LATCH_EN   (0x20)
#define BIT_LPA_CYCLE   (0x20)
#define BIT_MOT_INT_EN   (0x40)
#define BIT_RESET   (0x80)
#define BIT_S0_DELAY_EN   (0x01)
#define BIT_S2_DELAY_EN   (0x04)
#define BIT_SLAVE_BYTE_SW   (0x40)
#define BIT_SLAVE_EN   (0x80)
#define BIT_SLAVE_GROUP   (0x10)
#define BIT_SLEEP   (0x40)
#define BIT_STBY_XA   (0x20)
#define BIT_STBY_XG   (0x04)
#define BIT_STBY_XYZA   (BIT_STBY_XA | BIT_STBY_YA | BIT_STBY_ZA)
#define BIT_STBY_XYZG   (BIT_STBY_XG | BIT_STBY_YG | BIT_STBY_ZG)
#define BIT_STBY_YA   (0x10)
#define BIT_STBY_YG   (0x02)
#define BIT_STBY_ZA   (0x08)
#define BIT_STBY_ZG   (0x01)
#define BITS_CLK   (0x07)
#define BITS_FSR   (0x18)
#define BITS_HPF   (0x07)
#define BITS_I2C_MASTER_DLY   (0x1F)
#define BITS_LPF   (0x07)
#define BITS_SLAVE_LENGTH   (0x0F)
#define BITS_WOM_EN   (0xC0)
#define delay_ms   delay
#define i2c_read   !I2Cdev::readBytes
#define i2c_write   !I2Cdev::writeBytes
#define LOAD_CHUNK   (16)
#define MAX_COMPASS_SAMPLE_RATE   (100)
#define MAX_PACKET_LENGTH   (12)
#define min(a, b)   ((a<b)?a:b)
#define MPU6050
#define SUPPORTS_AK89xx_HIGH_SENS   (0x00)

Enumerations

enum  accel_fsr_e {
  INV_FSR_2G = 0, INV_FSR_4G, INV_FSR_8G, INV_FSR_16G,
  NUM_ACCEL_FSR
}
enum  clock_sel_e { INV_CLK_INTERNAL = 0, INV_CLK_PLL, NUM_CLK }
enum  gyro_fsr_e {
  INV_FSR_250DPS = 0, INV_FSR_500DPS, INV_FSR_1000DPS, INV_FSR_2000DPS,
  NUM_GYRO_FSR
}
enum  lp_accel_rate_e { INV_LPA_1_25HZ, INV_LPA_5HZ, INV_LPA_20HZ, INV_LPA_40HZ }
enum  lpf_e {
  INV_FILTER_256HZ_NOLPF2 = 0, INV_FILTER_188HZ, INV_FILTER_98HZ, INV_FILTER_42HZ,
  INV_FILTER_20HZ, INV_FILTER_10HZ, INV_FILTER_5HZ, INV_FILTER_2100HZ_NOLPF,
  NUM_FILTER
}

Functions

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.
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.
static int reg_int_cb (struct int_param_s *int_param)
static int set_int_enable (unsigned char enable)
 Enable/disable data ready interrupt. If the DMP is on, the DMP interrupt is enabled. Otherwise, the data ready interrupt is used.
static int setup_compass (void)

Variables

static int deviceIndex = 0
struct gyro_state_s gyroArray [MPU_MAX_DEVICES]
struct hw_shw
struct hw_s hwArray [MPU_MAX_DEVICES]
struct gyro_reg_sreg
struct gyro_reg_s regArray [MPU_MAX_DEVICES]
struct gyro_state_sst
struct test_stest
struct test_s testArray [MPU_MAX_DEVICES]

Define Documentation

#define LOAD_CHUNK   (16)


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