#elif defined MOTION_DRIVER_TARGET_MSP430
#include "msp430.h"
#include "msp430_i2c.h"
#include "msp430_clock.h"
#include "msp430_interrupt.h"
#define i2c_write msp430_i2c_write
#define i2c_read msp430_i2c_read
#define delay_ms msp430_delay_ms
#define get_ms msp430_get_clock_ms
static inline int reg_int_cb(struct int_param_s *int_param)
{
return msp430_reg_int_cb(int_param->cb, int_param->pin, int_param->lp_exit,
int_param->active_low);
}
#define log_i(...) do {} while (0)
#define log_e(...) do {} while (0)
/* labs is already defined by TI's toolchain. */
/* fabs is for doubles. fabsf is for floats. */
#define fabs fabsf
#define min(a,b) ((a<b)?a:b)
#elif defined EMPL_TARGET_MSP430
#include "msp430.h"
#include "msp430_i2c.h"
#include "msp430_clock.h"
#include "msp430_interrupt.h"
#include "log.h"
#define i2c_write msp430_i2c_write
#define i2c_read msp430_i2c_read
#define delay_ms msp430_delay_ms
#define get_ms msp430_get_clock_ms
static inline int reg_int_cb(struct int_param_s *int_param)
{
return msp430_reg_int_cb(int_param->cb, int_param->pin, int_param->lp_exit,
int_param->active_low);
}
#define log_i MPL_LOGI
#define log_e MPL_LOGE
/* labs is already defined by TI's toolchain. */
/* fabs is for doubles. fabsf is for floats. */
#define fabs fabsf
#define min(a,b) ((a<b)?a:b)
#elif defined EMPL_TARGET_UC3L0
/* Instead of using the standard TWI driver from the ASF library, we're using
* a TWI driver that follows the slave address + register address convention.
*/
#include "twi.h"
#include "delay.h"
#include "sysclk.h"
#include "log.h"
#include "sensors_xplained.h"
#include "uc3l0_clock.h"
#define i2c_write(a, b, c, d) twi_write(a, b, d, c)
#define i2c_read(a, b, c, d) twi_read(a, b, d, c)
/* delay_ms is a function already defined in ASF. */
#define get_ms uc3l0_get_clock_ms
static inline int reg_int_cb(struct int_param_s *int_param)
{
sensor_board_irq_connect(int_param->pin, int_param->cb, int_param->arg);
return 0;
}
#define log_i MPL_LOGI
#define log_e MPL_LOGE
/* UC3 is a 32-bit processor, so abs and labs are equivalent. */
#define labs abs
#define fabs(x) (((x)>0)?(x):-(x))
#else
#error Gyro driver is missing the system layer implementations.
#endif
#if !defined MPU6050 && !defined MPU9150 && !defined MPU6500 && !defined MPU9250
#error Which gyro are you using? Define MPUxxxx in your compiler options.
#endif
/* Time for some messy macro work. =]
* #define MPU9150
* is equivalent to..
* #define MPU6050
* #define AK8975_SECONDARY
*
* #define MPU9250
* is equivalent to..
* #define MPU6500
* #define AK8963_SECONDARY
*/
#if defined MPU9150
#ifndef MPU6050
#define MPU6050
#endif /* #ifndef MPU6050 */
#if defined AK8963_SECONDARY
#error "MPU9150 and AK8963_SECONDARY cannot both be defined."
#elif !defined AK8975_SECONDARY /* #if defined AK8963_SECONDARY */
#define AK8975_SECONDARY
#endif /* #if defined AK8963_SECONDARY */
#elif defined MPU9250 /* #if defined MPU9150 */
#ifndef MPU6500
#define MPU6500
#endif /* #ifndef MPU6500 */
#if defined AK8975_SECONDARY
#error "MPU9250 and AK8975_SECONDARY cannot both be defined."
#elif !defined AK8963_SECONDARY /* #if defined AK8975_SECONDARY */
#define AK8963_SECONDARY
#endif /* #if defined AK8975_SECONDARY */
#endif /* #if defined MPU9150 */
#if defined AK8975_SECONDARY || defined AK8963_SECONDARY
#define AK89xx_SECONDARY
#else
/* #warning "No compass = less profit for Invensense. Lame." */
#endif
/* Information specific to a particular device. */
struct hw_s {
unsigned char addr;
unsigned short max_fifo;
unsigned char num_reg;
unsigned short temp_sens;
short temp_offset;
unsigned short bank_size;
#if defined AK89xx_SECONDARY
unsigned short compass_fsr;
#endif
};
/* When entering motion interrupt mode, the driver keeps track of the
* previous state so that it can be restored at a later time.
* TODO: This is tacky. Fix it.
*/
struct motion_int_cache_s {
unsigned short gyro_fsr;
unsigned char accel_fsr;
unsigned short lpf;
unsigned short sample_rate;
unsigned char sensors_on;
unsigned char fifo_sensors;
unsigned char dmp_on;
};
/* Cached chip configuration data.
* TODO: A lot of these can be handled with a bitmask.
*/
struct chip_cfg_s {
/* Matches gyro_cfg >> 3 & 0x03 */
unsigned char gyro_fsr;
/* Matches accel_cfg >> 3 & 0x03 */
unsigned char accel_fsr;
/* Enabled sensors. Uses same masks as fifo_en, NOT pwr_mgmt_2. */
unsigned char sensors;
/* Matches config register. */
unsigned char lpf;
unsigned char clk_src;
/* Sample rate, NOT rate divider. */
unsigned short sample_rate;
/* Matches fifo_en register. */
unsigned char fifo_enable;
/* Matches int enable register. */
unsigned char int_enable;
/* 1 if devices on auxiliary I2C bus appear on the primary. */
unsigned char bypass_mode;
/* 1 if half-sensitivity.
* NOTE: This doesn't belong here, but everything else in hw_s is const,
* and this allows us to save some precious RAM.
*/
unsigned char accel_half;
/* 1 if device in low-power accel-only mode. */
unsigned char lp_accel_mode;
/* 1 if interrupts are only triggered on motion events. */
unsigned char int_motion_only;
struct motion_int_cache_s cache;
/* 1 for active low interrupts. */
unsigned char active_low_int;
/* 1 for latched interrupts. */
unsigned char latched_int;
/* 1 if DMP is enabled. */
unsigned char dmp_on;
/* Ensures that DMP will only be loaded once. */
unsigned char dmp_loaded;
/* Sampling rate used when DMP is enabled. */
unsigned short dmp_sample_rate;
#ifdef AK89xx_SECONDARY
/* Compass sample rate. */
unsigned short compass_sample_rate;
unsigned char compass_addr;
short mag_sens_adj[3];
#endif
};
/* Information for self-test. */
struct test_s {
unsigned long gyro_sens;
unsigned long accel_sens;
unsigned char reg_rate_div;
unsigned char reg_lpf;
unsigned char reg_gyro_fsr;
unsigned char reg_accel_fsr;
unsigned short wait_ms;
unsigned char packet_thresh;
float min_dps;
float max_dps;
float max_gyro_var;
float min_g;
float max_g;
float max_accel_var;
#ifdef MPU6500
float max_g_offset;
unsigned short sample_wait_ms;
#endif
};
#ifdef AK89xx_SECONDARY
static int setup_compass(void);
#define MAX_COMPASS_SAMPLE_RATE (100)
#endif
/**
* @brief Enable/disable data ready interrupt.
* If the DMP is on, the DMP interrupt is enabled. Otherwise, the data ready
* interrupt is used.
* @param[in] enable 1 to enable interrupt.
* @return 0 if successful.
*/
static int set_int_enable(unsigned char enable)
{
unsigned char tmp;
if (st.chip_cfg.dmp_on) {
if (enable)
tmp = BIT_DMP_INT_EN;
else
tmp = 0x00;
if (i2c_write(st.hw->addr, st.reg->int_enable, 1, &tmp))
return -1;
st.chip_cfg.int_enable = tmp;
} else {
if (!st.chip_cfg.sensors)
return -1;
if (enable && st.chip_cfg.int_enable)
return 0;
if (enable)
tmp = BIT_DATA_RDY_EN;
else
tmp = 0x00;
if (i2c_write(st.hw->addr, st.reg->int_enable, 1, &tmp))
return -1;
st.chip_cfg.int_enable = tmp;
}
return 0;
}
/**
* @brief Register dump for testing.
* @return 0 if successful.
*/
int mpu_reg_dump(void)
{
unsigned char ii;
unsigned char data;
for (ii = 0; ii < st.hw->num_reg; ii++) {
if (ii == st.reg->fifo_r_w || ii == st.reg->mem_r_w)
continue;
if (i2c_read(st.hw->addr, ii, 1, &data))
return -1;
log_i("%#5x: %#5x\r\n", ii, data);
}
return 0;
}
/**
* @brief Read from a single register.
* NOTE: The memory and FIFO read/write registers cannot be accessed.
* @param[in] reg Register address.
* @param[out] data Register data.
* @return 0 if successful.
*/
int mpu_read_reg(unsigned char reg, unsigned char *data)
{
if (reg == st.reg->fifo_r_w || reg == st.reg->mem_r_w)
return -1;
if (reg >= st.hw->num_reg)
return -1;
return i2c_read(st.hw->addr, reg, 1, data);
}
/* Wake up chip. */
data[0] = 0x00;
if (i2c_write(st.hw->addr, st.reg->pwr_mgmt_1, 1, data))
return -1;
st.chip_cfg.accel_half = 0;
#ifdef MPU6500
/* MPU6500 shares 4kB of memory between the DMP and the FIFO. Since the
* first 3kB are needed by the DMP, we'll use the last 1kB for the FIFO.
*/
data[0] = BIT_FIFO_SIZE_1024 | 0x8;
if (i2c_write(st.hw->addr, st.reg->accel_cfg2, 1, data))
return -1;
#endif
/* Set to invalid values to ensure no I2C writes are skipped. */
st.chip_cfg.sensors = 0xFF;
st.chip_cfg.gyro_fsr = 0xFF;
st.chip_cfg.accel_fsr = 0xFF;
st.chip_cfg.lpf = 0xFF;
st.chip_cfg.sample_rate = 0xFFFF;
st.chip_cfg.fifo_enable = 0xFF;
st.chip_cfg.bypass_mode = 0xFF;
#ifdef AK89xx_SECONDARY
st.chip_cfg.compass_sample_rate = 0xFFFF;
#endif
/* mpu_set_sensors always preserves this setting. */
st.chip_cfg.clk_src = INV_CLK_PLL;
/* Handled in next call to mpu_set_bypass. */
st.chip_cfg.active_low_int = 1;
st.chip_cfg.latched_int = 0;
st.chip_cfg.int_motion_only = 0;
st.chip_cfg.lp_accel_mode = 0;
memset(&st.chip_cfg.cache, 0, sizeof(st.chip_cfg.cache));
st.chip_cfg.dmp_on = 0;
st.chip_cfg.dmp_loaded = 0;
st.chip_cfg.dmp_sample_rate = 0;
if (mpu_set_gyro_fsr(2000))
return -1;
if (mpu_set_accel_fsr(2))
return -1;
if (mpu_set_lpf(42))
return -1;
if (mpu_set_sample_rate(50))
return -1;
if (mpu_configure_fifo(0))
return -1;
#ifndef EMPL_TARGET_STM32F4
if (int_param)
reg_int_cb(int_param);
#endif
#ifdef AK89xx_SECONDARY
setup_compass();
if (mpu_set_compass_sample_rate(10))
return -1;
#else
/* Already disabled by setup_compass. */
if (mpu_set_bypass(0))
return -1;
#endif
mpu_set_sensors(0);
return 0;
}
/**
* @brief 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:
* \n MPU6050: 1.25Hz, 5Hz, 20Hz, 40Hz
* \n MPU6500: 1.25Hz, 2.5Hz, 5Hz, 10Hz, 20Hz, 40Hz, 80Hz, 160Hz, 320Hz, 640Hz
* \n 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.
* \n To select a fractional wake-up frequency, round down the value passed to
* @e rate.
* @param[in] rate Minimum sampling rate, or zero to disable LP
* accel mode.
* @return 0 if successful.
*/
int mpu_lp_accel_mode(unsigned short rate)
{
unsigned char tmp[2];
if (rate > 40)
return -1;
if (!rate) {
mpu_set_int_latched(0);
tmp[0] = 0;
tmp[1] = BIT_STBY_XYZG;
if (i2c_write(st.hw->addr, st.reg->pwr_mgmt_1, 2, tmp))
return -1;
st.chip_cfg.lp_accel_mode = 0;
return 0;
}
/* For LP accel, we automatically configure the hardware to produce latched
* interrupts. In LP accel mode, the hardware cycles into sleep mode before
* it gets a chance to deassert the interrupt pin; therefore, we shift this
* responsibility over to the MCU.
*
* Any register read will clear the interrupt.
*/
mpu_set_int_latched(1);
#if defined MPU6050
tmp[0] = BIT_LPA_CYCLE;
if (rate == 1) {
tmp[1] = INV_LPA_1_25HZ;
mpu_set_lpf(5);
} else if (rate <= 5) {
tmp[1] = INV_LPA_5HZ;
mpu_set_lpf(5);
} else if (rate <= 20) {
tmp[1] = INV_LPA_20HZ;
mpu_set_lpf(10);
} else {
tmp[1] = INV_LPA_40HZ;
mpu_set_lpf(20);
}
tmp[1] = (tmp[1] << 6) | BIT_STBY_XYZG;
if (i2c_write(st.hw->addr, st.reg->pwr_mgmt_1, 2, tmp))
return -1;
#elif defined MPU6500
/* Set wake frequency. */
if (rate == 1)
tmp[0] = INV_LPA_1_25HZ;
else if (rate == 2)
tmp[0] = INV_LPA_2_5HZ;
else if (rate <= 5)
tmp[0] = INV_LPA_5HZ;
else if (rate <= 10)
tmp[0] = INV_LPA_10HZ;
else if (rate <= 20)
tmp[0] = INV_LPA_20HZ;
else if (rate <= 40)
tmp[0] = INV_LPA_40HZ;
else if (rate <= 80)
tmp[0] = INV_LPA_80HZ;
else if (rate <= 160)
tmp[0] = INV_LPA_160HZ;
else if (rate <= 320)
tmp[0] = INV_LPA_320HZ;
else
tmp[0] = INV_LPA_640HZ;
if (i2c_write(st.hw->addr, st.reg->lp_accel_odr, 1, tmp))
return -1;
tmp[0] = BIT_LPA_CYCLE;
if (i2c_write(st.hw->addr, st.reg->pwr_mgmt_1, 1, tmp))
return -1;
#endif
st.chip_cfg.sensors = INV_XYZ_ACCEL;
st.chip_cfg.clk_src = 0;
st.chip_cfg.lp_accel_mode = 1;
mpu_configure_fifo(0);
return 0;
}
/**
* @brief Read raw gyro data directly from the registers.
* @param[out] data Raw data in hardware units.
* @param[out] timestamp Timestamp in milliseconds. Null if not needed.
* @return 0 if successful.
*/
int mpu_get_gyro_reg(short *data, unsigned long *timestamp)
{
unsigned char tmp[6];
if (!(st.chip_cfg.sensors & INV_XYZ_GYRO))
return -1;
/**
* @brief Read raw accel data directly from the registers.
* @param[out] data Raw data in hardware units.
* @param[out] timestamp Timestamp in milliseconds. Null if not needed.
* @return 0 if successful.
*/
int mpu_get_accel_reg(short *data, unsigned long *timestamp)
{
unsigned char tmp[6];
if (!(st.chip_cfg.sensors & INV_XYZ_ACCEL))
return -1;
/**
* @brief Read temperature data directly from the registers.
* @param[out] data Data in q16 format.
* @param[out] timestamp Timestamp in milliseconds. Null if not needed.
* @return 0 if successful.
*/
int mpu_get_temperature(long *data, unsigned long *timestamp)
{
unsigned char tmp[2];
short raw;
if (!(st.chip_cfg.sensors))
return -1;
if (i2c_read(st.hw->addr, st.reg->temp, 2, tmp))
return -1;
raw = (tmp[0] << 8) | tmp[1];
if (timestamp)
get_ms(timestamp);
/**
* @brief Read biases to the accel bias 6500 registers.
* This function reads from the MPU6500 accel offset cancellations registers.
* The format are G in +-8G format. The register is initialized with OTP
* factory trim values.
* @param[in] accel_bias returned structure with the accel bias
* @return 0 if successful.
*/
int mpu_read_6500_accel_bias(long *accel_bias) {
unsigned char data[6];
if (i2c_read(st.hw->addr, 0x77, 2, &data[0]))
return -1;
if (i2c_read(st.hw->addr, 0x7A, 2, &data[2]))
return -1;
if (i2c_read(st.hw->addr, 0x7D, 2, &data[4]))
return -1;
accel_bias[0] = ((long)data[0]<<8) | data[1];
accel_bias[1] = ((long)data[2]<<8) | data[3];
accel_bias[2] = ((long)data[4]<<8) | data[5];
return 0;
}
/**
* @brief Read biases to the accel bias 6050 registers.
* This function reads from the MPU6050 accel offset cancellations registers.
* The format are G in +-8G format. The register is initialized with OTP
* factory trim values.
* @param[in] accel_bias returned structure with the accel bias
* @return 0 if successful.
*/
int mpu_read_6050_accel_bias(long *accel_bias) {
unsigned char data[6];
if (i2c_read(st.hw->addr, 0x06, 2, &data[0]))
return -1;
if (i2c_read(st.hw->addr, 0x08, 2, &data[2]))
return -1;
if (i2c_read(st.hw->addr, 0x0A, 2, &data[4]))
return -1;
accel_bias[0] = ((long)data[0]<<8) | data[1];
accel_bias[1] = ((long)data[2]<<8) | data[3];
accel_bias[2] = ((long)data[4]<<8) | data[5];
return 0;
}
/**
* @brief Push biases to the gyro bias 6500/6050 registers.
* This function expects biases relative to the current sensor output, and
* these biases will be added to the factory-supplied values. Bias inputs are LSB
* in +-1000dps format.
* @param[in] gyro_bias New biases.
* @return 0 if successful.
*/
int mpu_set_gyro_bias_reg(long *gyro_bias)
{
unsigned char data[6] = {0, 0, 0, 0, 0, 0};
int i=0;
for(i=0;i<3;i++) {
gyro_bias= (-gyro_bias);
}
data[0] = (gyro_bias[0] >> 8) & 0xff;
data[1] = (gyro_bias[0]) & 0xff;
data[2] = (gyro_bias[1] >> 8) & 0xff;
data[3] = (gyro_bias[1]) & 0xff;
data[4] = (gyro_bias[2] >> 8) & 0xff;
data[5] = (gyro_bias[2]) & 0xff;
if (i2c_write(st.hw->addr, 0x13, 2, &data[0]))
return -1;
if (i2c_write(st.hw->addr, 0x15, 2, &data[2]))
return -1;
if (i2c_write(st.hw->addr, 0x17, 2, &data[4]))
return -1;
return 0;
}
/**
* @brief Push biases to the accel bias 6050 registers.
* This function expects biases relative to the current sensor output, and
* these biases will be added to the factory-supplied values. Bias inputs are LSB
* in +-16G format.
* @param[in] accel_bias New biases.
* @return 0 if successful.
*/
int mpu_set_accel_bias_6050_reg(const long *accel_bias) {
unsigned char data[6] = {0, 0, 0, 0, 0, 0};
long accel_reg_bias[3] = {0, 0, 0};
if (i2c_write(st.hw->addr, 0x06, 2, &data[0]))
return -1;
if (i2c_write(st.hw->addr, 0x08, 2, &data[2]))
return -1;
if (i2c_write(st.hw->addr, 0x0A, 2, &data[4]))
return -1;
return 0;
}
/**
* @brief Push biases to the accel bias 6500 registers.
* This function expects biases relative to the current sensor output, and
* these biases will be added to the factory-supplied values. Bias inputs are LSB
* in +-16G format.
* @param[in] accel_bias New biases.
* @return 0 if successful.
*/
int mpu_set_accel_bias_6500_reg(const long *accel_bias) {
unsigned char data[6] = {0, 0, 0, 0, 0, 0};
long accel_reg_bias[3] = {0, 0, 0};
if (i2c_write(st.hw->addr, 0x77, 2, &data[0]))
return -1;
if (i2c_write(st.hw->addr, 0x7A, 2, &data[2]))
return -1;
if (i2c_write(st.hw->addr, 0x7D, 2, &data[4]))
return -1;
return 0;
}
/**
* @brief Reset FIFO read/write pointers.
* @return 0 if successful.
*/
int mpu_reset_fifo(void)
{
unsigned char data;
if (!(st.chip_cfg.sensors))
return -1;
data = 0;
if (i2c_write(st.hw->addr, st.reg->int_enable, 1, &data))
return -1;
if (i2c_write(st.hw->addr, st.reg->fifo_en, 1, &data))
return -1;
if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, &data))
return -1;
if (st.chip_cfg.dmp_on) {
data = BIT_FIFO_RST | BIT_DMP_RST;
if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, &data))
return -1;
delay_ms(50);
data = BIT_DMP_EN | BIT_FIFO_EN;
if (st.chip_cfg.sensors & INV_XYZ_COMPASS)
data |= BIT_AUX_IF_EN;
if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, &data))
return -1;
if (st.chip_cfg.int_enable)
data = BIT_DMP_INT_EN;
else
data = 0;
if (i2c_write(st.hw->addr, st.reg->int_enable, 1, &data))
return -1;
data = 0;
if (i2c_write(st.hw->addr, st.reg->fifo_en, 1, &data))
return -1;
} else {
data = BIT_FIFO_RST;
if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, &data))
return -1;
if (st.chip_cfg.bypass_mode || !(st.chip_cfg.sensors & INV_XYZ_COMPASS))
data = BIT_FIFO_EN;
else
data = BIT_FIFO_EN | BIT_AUX_IF_EN;
if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, &data))
return -1;
delay_ms(50);
if (st.chip_cfg.int_enable)
data = BIT_DATA_RDY_EN;
else
data = 0;
if (i2c_write(st.hw->addr, st.reg->int_enable, 1, &data))
return -1;
if (i2c_write(st.hw->addr, st.reg->fifo_en, 1, &st.chip_cfg.fifo_enable))
return -1;
}
return 0;
}
/**
* @brief Get the gyro full-scale range.
* @param[out] fsr Current full-scale range.
* @return 0 if successful.
*/
int mpu_get_gyro_fsr(unsigned short *fsr)
{
switch (st.chip_cfg.gyro_fsr) {
case INV_FSR_250DPS:
fsr[0] = 250;
break;
case INV_FSR_500DPS:
fsr[0] = 500;
break;
case INV_FSR_1000DPS:
fsr[0] = 1000;
break;
case INV_FSR_2000DPS:
fsr[0] = 2000;
break;
default:
fsr[0] = 0;
break;
}
return 0;
}
/**
* @brief Set the gyro full-scale range.
* @param[in] fsr Desired full-scale range.
* @return 0 if successful.
*/
int mpu_set_gyro_fsr(unsigned short fsr)
{
unsigned char data;
if (!(st.chip_cfg.sensors))
return -1;
switch (fsr) {
case 250:
data = INV_FSR_250DPS << 3;
break;
case 500:
data = INV_FSR_500DPS << 3;
break;
case 1000:
data = INV_FSR_1000DPS << 3;
break;
case 2000:
data = INV_FSR_2000DPS << 3;
break;
default:
return -1;
}
if (st.chip_cfg.gyro_fsr == (data >> 3))
return 0;
if (i2c_write(st.hw->addr, st.reg->gyro_cfg, 1, &data))
return -1;
st.chip_cfg.gyro_fsr = data >> 3;
return 0;
}
/**
* @brief Get the accel full-scale range.
* @param[out] fsr Current full-scale range.
* @return 0 if successful.
*/
int mpu_get_accel_fsr(unsigned char *fsr)
{
switch (st.chip_cfg.accel_fsr) {
case INV_FSR_2G:
fsr[0] = 2;
break;
case INV_FSR_4G:
fsr[0] = 4;
break;
case INV_FSR_8G:
fsr[0] = 8;
break;
case INV_FSR_16G:
fsr[0] = 16;
break;
default:
return -1;
}
if (st.chip_cfg.accel_half)
fsr[0] <<= 1;
return 0;
}
/**
* @brief Set the accel full-scale range.
* @param[in] fsr Desired full-scale range.
* @return 0 if successful.
*/
int mpu_set_accel_fsr(unsigned char fsr)
{
unsigned char data;
if (!(st.chip_cfg.sensors))
return -1;
switch (fsr) {
case 2:
data = INV_FSR_2G << 3;
break;
case 4:
data = INV_FSR_4G << 3;
break;
case 8:
data = INV_FSR_8G << 3;
break;
case 16:
data = INV_FSR_16G << 3;
break;
default:
return -1;
}
if (st.chip_cfg.accel_fsr == (data >> 3))
return 0;
if (i2c_write(st.hw->addr, st.reg->accel_cfg, 1, &data))
return -1;
st.chip_cfg.accel_fsr = data >> 3;
return 0;
}
/**
* @brief Get the current DLPF setting.
* @param[out] lpf Current LPF setting.
* 0 if successful.
*/
int mpu_get_lpf(unsigned short *lpf)
{
switch (st.chip_cfg.lpf) {
case INV_FILTER_188HZ:
lpf[0] = 188;
break;
case INV_FILTER_98HZ:
lpf[0] = 98;
break;
case INV_FILTER_42HZ:
lpf[0] = 42;
break;
case INV_FILTER_20HZ:
lpf[0] = 20;
break;
case INV_FILTER_10HZ:
lpf[0] = 10;
break;
case INV_FILTER_5HZ:
lpf[0] = 5;
break;
case INV_FILTER_256HZ_NOLPF2:
case INV_FILTER_2100HZ_NOLPF:
default:
lpf[0] = 0;
break;
}
return 0;
}
/**
* @brief Set digital low pass filter.
* The following LPF settings are supported: 188, 98, 42, 20, 10, 5.
* @param[in] lpf Desired LPF setting.
* @return 0 if successful.
*/
int mpu_set_lpf(unsigned short lpf)
{
unsigned char data;
if (!(st.chip_cfg.sensors))
return -1;
if (lpf >= 188)
data = INV_FILTER_188HZ;
else if (lpf >= 98)
data = INV_FILTER_98HZ;
else if (lpf >= 42)
data = INV_FILTER_42HZ;
else if (lpf >= 20)
data = INV_FILTER_20HZ;
else if (lpf >= 10)
data = INV_FILTER_10HZ;
else
data = INV_FILTER_5HZ;
if (st.chip_cfg.lpf == data)
return 0;
if (i2c_write(st.hw->addr, st.reg->lpf, 1, &data))
return -1;
st.chip_cfg.lpf = data;
return 0;
}
/**
* @brief Get sampling rate.
* @param[out] rate Current sampling rate (Hz).
* @return 0 if successful.
*/
int mpu_get_sample_rate(unsigned short *rate)
{
if (st.chip_cfg.dmp_on)
return -1;
else
rate[0] = st.chip_cfg.sample_rate;
return 0;
}
/**
* @brief Set sampling rate.
* Sampling rate must be between 4Hz and 1kHz.
* @param[in] rate Desired sampling rate (Hz).
* @return 0 if successful.
*/
int mpu_set_sample_rate(unsigned short rate)
{
unsigned char data;
if (!(st.chip_cfg.sensors))
return -1;
if (st.chip_cfg.dmp_on)
return -1;
else {
if (st.chip_cfg.lp_accel_mode) {
if (rate && (rate <= 40)) {
/* Just stay in low-power accel mode. */
mpu_lp_accel_mode(rate);
return 0;
}
/* Requested rate exceeds the allowed frequencies in LP accel mode,
* switch back to full-power mode.
*/
mpu_lp_accel_mode(0);
}
if (rate < 4)
rate = 4;
else if (rate > 1000)
rate = 1000;
data = 1000 / rate - 1;
if (i2c_write(st.hw->addr, st.reg->rate_div, 1, &data))
return -1;
/* Automatically set LPF to 1/2 sampling rate. */
mpu_set_lpf(st.chip_cfg.sample_rate >> 1);
return 0;
}
}
/**
* @brief Get compass sampling rate.
* @param[out] rate Current compass sampling rate (Hz).
* @return 0 if successful.
*/
int mpu_get_compass_sample_rate(unsigned short *rate)
{
#ifdef AK89xx_SECONDARY
rate[0] = st.chip_cfg.compass_sample_rate;
return 0;
#else
rate[0] = 0;
return -1;
#endif
}
/**
* @brief 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.
*
* \n WARNING: The new rate may be different than what was requested. Call
* mpu_get_compass_sample_rate to check the actual setting.
* @param[in] rate Desired compass sampling rate (Hz).
* @return 0 if successful.
*/
int mpu_set_compass_sample_rate(unsigned short rate)
{
#ifdef AK89xx_SECONDARY
unsigned char div;
if (!rate || rate > st.chip_cfg.sample_rate || rate > MAX_COMPASS_SAMPLE_RATE)
return -1;
/**
* @brief Get gyro sensitivity scale factor.
* @param[out] sens Conversion from hardware units to dps.
* @return 0 if successful.
*/
int mpu_get_gyro_sens(float *sens)
{
switch (st.chip_cfg.gyro_fsr) {
case INV_FSR_250DPS:
sens[0] = 131.f;
break;
case INV_FSR_500DPS:
sens[0] = 65.5f;
break;
case INV_FSR_1000DPS:
sens[0] = 32.8f;
break;
case INV_FSR_2000DPS:
sens[0] = 16.4f;
break;
default:
return -1;
}
return 0;
}
/**
* @brief Get accel sensitivity scale factor.
* @param[out] sens Conversion from hardware units to g's.
* @return 0 if successful.
*/
int mpu_get_accel_sens(unsigned short *sens)
{
switch (st.chip_cfg.accel_fsr) {
case INV_FSR_2G:
sens[0] = 16384;
break;
case INV_FSR_4G:
sens[0] = 8192;
break;
case INV_FSR_8G:
sens[0] = 4096;
break;
case INV_FSR_16G:
sens[0] = 2048;
break;
default:
return -1;
}
if (st.chip_cfg.accel_half)
sens[0] >>= 1;
return 0;
}
/**
* @brief Get current FIFO configuration.
* @e sensors can contain a combination of the following flags:
* \n INV_X_GYRO, INV_Y_GYRO, INV_Z_GYRO
* \n INV_XYZ_GYRO
* \n INV_XYZ_ACCEL
* @param[out] sensors Mask of sensors in FIFO.
* @return 0 if successful.
*/
int mpu_get_fifo_config(unsigned char *sensors)
{
sensors[0] = st.chip_cfg.fifo_enable;
return 0;
}
/**
* @brief Select which sensors are pushed to FIFO.
* @e sensors can contain a combination of the following flags:
* \n INV_X_GYRO, INV_Y_GYRO, INV_Z_GYRO
* \n INV_XYZ_GYRO
* \n INV_XYZ_ACCEL
* @param[in] sensors Mask of sensors to push to FIFO.
* @return 0 if successful.
*/
int mpu_configure_fifo(unsigned char sensors)
{
unsigned char prev;
int result = 0;
/* Compass data isn't going into the FIFO. Stop trying. */
sensors &= ~INV_XYZ_COMPASS;
if (st.chip_cfg.dmp_on)
return 0;
else {
if (!(st.chip_cfg.sensors))
return -1;
prev = st.chip_cfg.fifo_enable;
st.chip_cfg.fifo_enable = sensors & st.chip_cfg.sensors;
if (st.chip_cfg.fifo_enable != sensors)
/* You're not getting what you asked for. Some sensors are
* asleep.
*/
result = -1;
else
result = 0;
if (sensors || st.chip_cfg.lp_accel_mode)
set_int_enable(1);
else
set_int_enable(0);
if (sensors) {
if (mpu_reset_fifo()) {
st.chip_cfg.fifo_enable = prev;
return -1;
}
}
}
return result;
}
/**
* @brief Get current power state.
* @param[in] power_on 1 if turned on, 0 if suspended.
* @return 0 if successful.
*/
int mpu_get_power_state(unsigned char *power_on)
{
if (st.chip_cfg.sensors)
power_on[0] = 1;
else
power_on[0] = 0;
return 0;
}
/**
* @brief Turn specific sensors on/off.
* @e sensors can contain a combination of the following flags:
* \n INV_X_GYRO, INV_Y_GYRO, INV_Z_GYRO
* \n INV_XYZ_GYRO
* \n INV_XYZ_ACCEL
* \n INV_XYZ_COMPASS
* @param[in] sensors Mask of sensors to wake.
* @return 0 if successful.
*/
int mpu_set_sensors(unsigned char sensors)
{
unsigned char data;
#ifdef AK89xx_SECONDARY
unsigned char user_ctrl;
#endif
if (sensors & INV_XYZ_GYRO)
data = INV_CLK_PLL;
else if (sensors)
data = 0;
else
data = BIT_SLEEP;
if (i2c_write(st.hw->addr, st.reg->pwr_mgmt_1, 1, &data)) {
st.chip_cfg.sensors = 0;
return -1;
}
st.chip_cfg.clk_src = data & ~BIT_SLEEP;
data = 0;
if (!(sensors & INV_X_GYRO))
data |= BIT_STBY_XG;
if (!(sensors & INV_Y_GYRO))
data |= BIT_STBY_YG;
if (!(sensors & INV_Z_GYRO))
data |= BIT_STBY_ZG;
if (!(sensors & INV_XYZ_ACCEL))
data |= BIT_STBY_XYZA;
if (i2c_write(st.hw->addr, st.reg->pwr_mgmt_2, 1, &data)) {
st.chip_cfg.sensors = 0;
return -1;
}
if (sensors && (sensors != INV_XYZ_ACCEL))
/* Latched interrupts only used in LP accel mode. */
mpu_set_int_latched(0);
#ifdef AK89xx_SECONDARY
#ifdef AK89xx_BYPASS
if (sensors & INV_XYZ_COMPASS)
mpu_set_bypass(1);
else
mpu_set_bypass(0);
#else
if (i2c_read(st.hw->addr, st.reg->user_ctrl, 1, &user_ctrl))
return -1;
/* Handle AKM power management. */
if (sensors & INV_XYZ_COMPASS) {
data = AKM_SINGLE_MEASUREMENT;
user_ctrl |= BIT_AUX_IF_EN;
} else {
data = AKM_POWER_DOWN;
user_ctrl &= ~BIT_AUX_IF_EN;
}
if (st.chip_cfg.dmp_on)
user_ctrl |= BIT_DMP_EN;
else
user_ctrl &= ~BIT_DMP_EN;
if (i2c_write(st.hw->addr, st.reg->s1_do, 1, &data))
return -1;
/* Enable/disable I2C master mode. */
if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, &user_ctrl))
return -1;
#endif
#endif
/**
* @brief Read the MPU interrupt status registers.
* @param[out] status Mask of interrupt bits.
* @return 0 if successful.
*/
int mpu_get_int_status(short *status)
{
unsigned char tmp[2];
if (!st.chip_cfg.sensors)
return -1;
if (i2c_read(st.hw->addr, st.reg->dmp_int_status, 2, tmp))
return -1;
status[0] = (tmp[0] << 8) | tmp[1];
return 0;
}
/**
* @brief Get one packet from the FIFO.
* If @e sensors does not contain a particular sensor, disregard the data
* returned to that pointer.
* \n @e sensors can contain a combination of the following flags:
* \n INV_X_GYRO, INV_Y_GYRO, INV_Z_GYRO
* \n INV_XYZ_GYRO
* \n INV_XYZ_ACCEL
* \n If the FIFO has no new data, @e sensors will be zero.
* \n If the FIFO is disabled, @e sensors will be zero and this function will
* return a non-zero error code.
* @param[out] gyro Gyro data in hardware units.
* @param[out] accel Accel data in hardware units.
* @param[out] timestamp Timestamp in milliseconds.
* @param[out] sensors Mask of sensors read from FIFO.
* @param[out] more Number of remaining packets.
* @return 0 if successful.
*/
int mpu_read_fifo(short *gyro, short *accel, unsigned long *timestamp,
unsigned char *sensors, unsigned char *more)
{
/* Assumes maximum packet size is gyro (6) + accel (6). */
unsigned char data[MAX_PACKET_LENGTH];
unsigned char packet_size = 0;
unsigned short fifo_count, index = 0;
if (st.chip_cfg.dmp_on)
return -1;
sensors[0] = 0;
if (!st.chip_cfg.sensors)
return -1;
if (!st.chip_cfg.fifo_enable)
return -1;
if (st.chip_cfg.fifo_enable & INV_X_GYRO)
packet_size += 2;
if (st.chip_cfg.fifo_enable & INV_Y_GYRO)
packet_size += 2;
if (st.chip_cfg.fifo_enable & INV_Z_GYRO)
packet_size += 2;
if (st.chip_cfg.fifo_enable & INV_XYZ_ACCEL)
packet_size += 6;
/**
* @brief Get one unparsed packet from the FIFO.
* This function should be used if the packet is to be parsed elsewhere.
* @param[in] length Length of one FIFO packet.
* @param[in] data FIFO packet.
* @param[in] more Number of remaining packets.
*/
int mpu_read_fifo_stream(unsigned short length, unsigned char *data,
unsigned char *more)
{
unsigned char tmp[2];
unsigned short fifo_count;
if (!st.chip_cfg.dmp_on)
return -1;
if (!st.chip_cfg.sensors)
return -1;
if (i2c_read(st.hw->addr, st.reg->fifo_count_h, 2, tmp))
return -1;
fifo_count = (tmp[0] << 8) | tmp[1];
if (fifo_count < length) {
more[0] = 0;
return -1;
}
if (fifo_count > (st.hw->max_fifo >> 1)) {
/* FIFO is 50% full, better check overflow bit. */
if (i2c_read(st.hw->addr, st.reg->int_status, 1, tmp))
return -1;
if (tmp[0] & BIT_FIFO_OVERFLOW) {
mpu_reset_fifo();
return -2;
}
}
/**
* @brief Set device to bypass mode.
* @param[in] bypass_on 1 to enable bypass mode.
* @return 0 if successful.
*/
int mpu_set_bypass(unsigned char bypass_on)
{
unsigned char tmp;
if (st.chip_cfg.bypass_mode == bypass_on)
return 0;
if (bypass_on) {
if (i2c_read(st.hw->addr, st.reg->user_ctrl, 1, &tmp))
return -1;
tmp &= ~BIT_AUX_IF_EN;
if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, &tmp))
return -1;
delay_ms(3);
tmp = BIT_BYPASS_EN;
if (st.chip_cfg.active_low_int)
tmp |= BIT_ACTL;
if (st.chip_cfg.latched_int)
tmp |= BIT_LATCH_EN | BIT_ANY_RD_CLR;
if (i2c_write(st.hw->addr, st.reg->int_pin_cfg, 1, &tmp))
return -1;
} else {
/* Enable I2C master mode if compass is being used. */
if (i2c_read(st.hw->addr, st.reg->user_ctrl, 1, &tmp))
return -1;
if (st.chip_cfg.sensors & INV_XYZ_COMPASS)
tmp |= BIT_AUX_IF_EN;
else
tmp &= ~BIT_AUX_IF_EN;
if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, &tmp))
return -1;
delay_ms(3);
if (st.chip_cfg.active_low_int)
tmp = BIT_ACTL;
else
tmp = 0;
if (st.chip_cfg.latched_int)
tmp |= BIT_LATCH_EN | BIT_ANY_RD_CLR;
if (i2c_write(st.hw->addr, st.reg->int_pin_cfg, 1, &tmp))
return -1;
}
st.chip_cfg.bypass_mode = bypass_on;
return 0;
}
/**
* @brief Set interrupt level.
* @param[in] active_low 1 for active low, 0 for active high.
* @return 0 if successful.
*/
int mpu_set_int_level(unsigned char active_low)
{
st.chip_cfg.active_low_int = active_low;
return 0;
}
/**
* @brief Enable latched interrupts.
* Any MPU register will clear the interrupt.
* @param[in] enable 1 to enable, 0 to disable.
* @return 0 if successful.
*/
int mpu_set_int_latched(unsigned char enable)
{
unsigned char tmp;
if (st.chip_cfg.latched_int == enable)
return 0;
if (enable)
tmp = BIT_LATCH_EN | BIT_ANY_RD_CLR;
else
tmp = 0;
if (st.chip_cfg.bypass_mode)
tmp |= BIT_BYPASS_EN;
if (st.chip_cfg.active_low_int)
tmp |= BIT_ACTL;
if (i2c_write(st.hw->addr, st.reg->int_pin_cfg, 1, &tmp))
return -1;
st.chip_cfg.latched_int = enable;
return 0;
}
static int gyro_self_test(long *bias_regular, long *bias_st)
{
int jj, result = 0;
unsigned char tmp[3];
float st_shift, st_shift_cust, st_shift_var;
if (i2c_read(st.hw->addr, 0x0D, 3, tmp))
return 0x07;
tmp[0] &= 0x1F;
tmp[1] &= 0x1F;
tmp[2] &= 0x1F;
for (jj = 0; jj < 3; jj++) {
st_shift_cust = labs(bias_regular[jj] - bias_st[jj]) / 65536.f;
if (tmp[jj]) {
st_shift = 3275.f / test.gyro_sens;
while (--tmp[jj])
st_shift *= 1.046f;
st_shift_var = st_shift_cust / st_shift - 1.f;
if (fabs(st_shift_var) > test.max_gyro_var)
result |= 1 << jj;
} else if ((st_shift_cust < test.min_dps) ||
(st_shift_cust > test.max_dps))
result |= 1 << jj;
}
return result;
}
#endif
#ifdef AK89xx_SECONDARY
static int compass_self_test(void)
{
unsigned char tmp[6];
unsigned char tries = 10;
int result = 0x07;
short data;
mpu_set_bypass(1);
tmp[0] = AKM_POWER_DOWN;
if (i2c_write(st.chip_cfg.compass_addr, AKM_REG_CNTL, 1, tmp))
return 0x07;
tmp[0] = AKM_BIT_SELF_TEST;
if (i2c_write(st.chip_cfg.compass_addr, AKM_REG_ASTC, 1, tmp))
goto AKM_restore;
tmp[0] = AKM_MODE_SELF_TEST;
if (i2c_write(st.chip_cfg.compass_addr, AKM_REG_CNTL, 1, tmp))
goto AKM_restore;
do {
delay_ms(10);
if (i2c_read(st.chip_cfg.compass_addr, AKM_REG_ST1, 1, tmp))
goto AKM_restore;
if (tmp[0] & AKM_DATA_READY)
break;
} while (tries--);
if (!(tmp[0] & AKM_DATA_READY))
goto AKM_restore;
if (i2c_read(st.chip_cfg.compass_addr, AKM_REG_HXL, 6, tmp))
goto AKM_restore;
result = 0;
#if defined MPU9150
data = (short)(tmp[1] << 8) | tmp[0];
if ((data > 100) || (data < -100))
result |= 0x01;
data = (short)(tmp[3] << 8) | tmp[2];
if ((data > 100) || (data < -100))
result |= 0x02;
data = (short)(tmp[5] << 8) | tmp[4];
if ((data > -300) || (data < -1000))
result |= 0x04;
#elif defined MPU9250
data = (short)(tmp[1] << 8) | tmp[0];
if ((data > 200) || (data < -200))
result |= 0x01;
data = (short)(tmp[3] << 8) | tmp[2];
if ((data > 200) || (data < -200))
result |= 0x02;
data = (short)(tmp[5] << 8) | tmp[4];
if ((data > -800) || (data < -3200))
result |= 0x04;
#endif
AKM_restore:
tmp[0] = 0 | SUPPORTS_AK89xx_HIGH_SENS;
i2c_write(st.chip_cfg.compass_addr, AKM_REG_ASTC, 1, tmp);
tmp[0] = SUPPORTS_AK89xx_HIGH_SENS;
i2c_write(st.chip_cfg.compass_addr, AKM_REG_CNTL, 1, tmp);
mpu_set_bypass(0);
return result;
}
#endif
static int get_st_biases(long *gyro, long *accel, unsigned char hw_test)
{
unsigned char data[MAX_PACKET_LENGTH];
unsigned char packet_count, ii;
unsigned short fifo_count;
data[0] = 0x01;
data[1] = 0;
if (i2c_write(st.hw->addr, st.reg->pwr_mgmt_1, 2, data))
return -1;
delay_ms(200);
data[0] = 0;
if (i2c_write(st.hw->addr, st.reg->int_enable, 1, data))
return -1;
if (i2c_write(st.hw->addr, st.reg->fifo_en, 1, data))
return -1;
if (i2c_write(st.hw->addr, st.reg->pwr_mgmt_1, 1, data))
return -1;
if (i2c_write(st.hw->addr, st.reg->i2c_mst, 1, data))
return -1;
if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, data))
return -1;
data[0] = BIT_FIFO_RST | BIT_DMP_RST;
if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, data))
return -1;
delay_ms(15);
data[0] = st.test->reg_lpf;
if (i2c_write(st.hw->addr, st.reg->lpf, 1, data))
return -1;
data[0] = st.test->reg_rate_div;
if (i2c_write(st.hw->addr, st.reg->rate_div, 1, data))
return -1;
if (hw_test)
data[0] = st.test->reg_gyro_fsr | 0xE0;
else
data[0] = st.test->reg_gyro_fsr;
if (i2c_write(st.hw->addr, st.reg->gyro_cfg, 1, data))
return -1;
if (hw_test)
data[0] = st.test->reg_accel_fsr | 0xE0;
else
data[0] = test.reg_accel_fsr;
if (i2c_write(st.hw->addr, st.reg->accel_cfg, 1, data))
return -1;
if (hw_test)
delay_ms(200);
/* Fill FIFO for test.wait_ms milliseconds. */
data[0] = BIT_FIFO_EN;
if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, data))
return -1;
if(result == 0) {
/* Self Test Pass/Fail Criteria C */
accel_offset_max = test.max_g_offset * 65536.f;
if(debug)
log_i("Accel:CRITERIA C: bias less than %7.4f\n", accel_offset_max/1.f);
for (i = 0; i < 3; i++) {
if(fabs(bias_regular) > accel_offset_max) {
if(debug)
log_i("FAILED: Accel axis:%d = %ld > 500mg\n", i, bias_regular);
result |= 1 << i; //Error condition
}
}
}
return result;
}
static int gyro_6500_self_test(long *bias_regular, long *bias_st, int debug)
{
int i, result = 0, otp_value_zero = 0;
float gyro_st_al_max;
float st_shift_cust[3], st_shift_ratio[3], ct_shift_prod[3], gyro_offset_max;
unsigned char regs[3];
if(result == 0) {
/* Self Test Pass/Fail Criteria C */
gyro_offset_max = test.min_dps * 65536.f;
if(debug)
log_i("Gyro:CRITERIA C: bias less than %7.4f\n", gyro_offset_max/1.f);
for (i = 0; i < 3; i++) {
if(fabs(bias_regular) > gyro_offset_max) {
if(debug)
log_i("FAILED: Gyro axis:%d = %ld > 20dps\n", i, bias_regular);
result |= 1 << i; //Error condition
}
}
}
return result;
}
static int get_st_6500_biases(long *gyro, long *accel, unsigned char hw_test, int debug)
{
unsigned char data[HWST_MAX_PACKET_LENGTH];
unsigned char packet_count, ii;
unsigned short fifo_count;
int s = 0, read_size = 0, ind;
data[0] = 0x01;
data[1] = 0;
if (i2c_write(st.hw->addr, st.reg->pwr_mgmt_1, 2, data))
return -1;
delay_ms(200);
data[0] = 0;
if (i2c_write(st.hw->addr, st.reg->int_enable, 1, data))
return -1;
if (i2c_write(st.hw->addr, st.reg->fifo_en, 1, data))
return -1;
if (i2c_write(st.hw->addr, st.reg->pwr_mgmt_1, 1, data))
return -1;
if (i2c_write(st.hw->addr, st.reg->i2c_mst, 1, data))
return -1;
if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, data))
return -1;
data[0] = BIT_FIFO_RST | BIT_DMP_RST;
if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, data))
return -1;
delay_ms(15);
data[0] = st.test->reg_lpf;
if (i2c_write(st.hw->addr, st.reg->lpf, 1, data))
return -1;
data[0] = st.test->reg_rate_div;
if (i2c_write(st.hw->addr, st.reg->rate_div, 1, data))
return -1;
if (hw_test)
data[0] = st.test->reg_gyro_fsr | 0xE0;
else
data[0] = st.test->reg_gyro_fsr;
if (i2c_write(st.hw->addr, st.reg->gyro_cfg, 1, data))
return -1;
if (hw_test)
data[0] = st.test->reg_accel_fsr | 0xE0;
else
data[0] = test.reg_accel_fsr;
if (i2c_write(st.hw->addr, st.reg->accel_cfg, 1, data))
return -1;
delay_ms(test.wait_ms); //wait 200ms for sensors to stabilize
return 0;
}
/**
* @brief Trigger gyro/accel/compass self-test for MPU6500/MPU9250
* On success/error, the self-test returns a mask representing the sensor(s)
* that failed. For each bit, a one (1) represents a "pass" case; conversely,
* a zero (0) indicates a failure.
*
* \n The mask is defined as follows:
* \n Bit 0: Gyro.
* \n Bit 1: Accel.
* \n Bit 2: Compass.
*
* @param[out] gyro Gyro biases in q16 format.
* @param[out] accel Accel biases (if applicable) in q16 format.
* @param[in] debug Debug flag used to print out more detailed logs. Must first set up logging in Motion Driver.
* @return Result mask (see above).
*/
int mpu_run_6500_self_test(long *gyro, long *accel, unsigned char debug)
{
const unsigned char tries = 2;
long gyro_st[3], accel_st[3];
unsigned char accel_result, gyro_result;
#ifdef AK89xx_SECONDARY
unsigned char compass_result;
#endif
int ii;
int result;
unsigned char accel_fsr, fifo_sensors, sensors_on;
unsigned short gyro_fsr, sample_rate, lpf;
unsigned char dmp_was_on;
for (ii = 0; ii < tries; ii++)
if (!get_st_6500_biases(gyro, accel, 0, debug))
break;
if (ii == tries) {
/* If we reach this point, we most likely encountered an I2C error.
* We'll just report an error for all three sensors.
*/
if(debug)
log_i("Retrieving Biases Error - possible I2C error\n");
result = 0;
goto restore;
}
if(debug)
log_i("Retrieving ST Biases\n");
for (ii = 0; ii < tries; ii++)
if (!get_st_6500_biases(gyro_st, accel_st, 1, debug))
break;
if (ii == tries) {
if(debug)
log_i("Retrieving ST Biases Error - possible I2C error\n");
/* Again, probably an I2C error. */
result = 0;
goto restore;
}
result = 0;
if (!gyro_result)
result |= 0x01;
if (!accel_result)
result |= 0x02;
#ifdef AK89xx_SECONDARY
compass_result = compass_self_test();
if(debug)
log_i("Compass Self Test Results: %d\n", compass_result);
if (!compass_result)
result |= 0x04;
#else
result |= 0x04;
#endif
restore:
if(debug)
log_i("Exiting HWST\n");
/* Set to invalid values to ensure no I2C writes are skipped. */
st.chip_cfg.gyro_fsr = 0xFF;
st.chip_cfg.accel_fsr = 0xFF;
st.chip_cfg.lpf = 0xFF;
st.chip_cfg.sample_rate = 0xFFFF;
st.chip_cfg.sensors = 0xFF;
st.chip_cfg.fifo_enable = 0xFF;
st.chip_cfg.clk_src = INV_CLK_PLL;
mpu_set_gyro_fsr(gyro_fsr);
mpu_set_accel_fsr(accel_fsr);
mpu_set_lpf(lpf);
mpu_set_sample_rate(sample_rate);
mpu_set_sensors(sensors_on);
mpu_configure_fifo(fifo_sensors);
if (dmp_was_on)
mpu_set_dmp_state(1);
return result;
}
#endif
/*
* \n This function must be called with the device either face-up or face-down
* (z-axis is parallel to gravity).
* @param[out] gyro Gyro biases in q16 format.
* @param[out] accel Accel biases (if applicable) in q16 format.
* @return Result mask (see above).
*/
int mpu_run_self_test(long *gyro, long *accel)
{
#ifdef MPU6050
const unsigned char tries = 2;
long gyro_st[3], accel_st[3];
unsigned char accel_result, gyro_result;
#ifdef AK89xx_SECONDARY
unsigned char compass_result;
#endif
int ii;
#endif
int result;
unsigned char accel_fsr, fifo_sensors, sensors_on;
unsigned short gyro_fsr, sample_rate, lpf;
unsigned char dmp_was_on;
/* For older chips, the self-test will be different. */
#if defined MPU6050
for (ii = 0; ii < tries; ii++)
if (!get_st_biases(gyro, accel, 0))
break;
if (ii == tries) {
/* If we reach this point, we most likely encountered an I2C error.
* We'll just report an error for all three sensors.
*/
result = 0;
goto restore;
}
for (ii = 0; ii < tries; ii++)
if (!get_st_biases(gyro_st, accel_st, 1))
break;
if (ii == tries) {
/* Again, probably an I2C error. */
result = 0;
goto restore;
}
accel_result = accel_self_test(accel, accel_st);
gyro_result = gyro_self_test(gyro, gyro_st);
result = 0;
if (!gyro_result)
result |= 0x01;
if (!accel_result)
result |= 0x02;
#ifdef AK89xx_SECONDARY
compass_result = compass_self_test();
if (!compass_result)
result |= 0x04;
#else
result |= 0x04;
#endif
restore:
#elif defined MPU6500
/* For now, this function will return a "pass" result for all three sensors
* for compatibility with current test applications.
*/
get_st_biases(gyro, accel, 0);
result = 0x7;
#endif
/* Set to invalid values to ensure no I2C writes are skipped. */
st.chip_cfg.gyro_fsr = 0xFF;
st.chip_cfg.accel_fsr = 0xFF;
st.chip_cfg.lpf = 0xFF;
st.chip_cfg.sample_rate = 0xFFFF;
st.chip_cfg.sensors = 0xFF;
st.chip_cfg.fifo_enable = 0xFF;
st.chip_cfg.clk_src = INV_CLK_PLL;
mpu_set_gyro_fsr(gyro_fsr);
mpu_set_accel_fsr(accel_fsr);
mpu_set_lpf(lpf);
mpu_set_sample_rate(sample_rate);
mpu_set_sensors(sensors_on);
mpu_configure_fifo(fifo_sensors);
if (dmp_was_on)
mpu_set_dmp_state(1);
return result;
}
/**
* @brief 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.
* @param[in] mem_addr Memory location (bank << 8 | start address)
* @param[in] length Number of bytes to write.
* @param[in] data Bytes to write to memory.
* @return 0 if successful.
*/
int mpu_write_mem(unsigned short mem_addr, unsigned short length,
unsigned char *data)
{
unsigned char tmp[2];
if (!data)
return -1;
if (!st.chip_cfg.sensors)
return -1;
/* Check bank boundaries. */
if (tmp[1] + length > st.hw->bank_size)
return -1;
if (i2c_write(st.hw->addr, st.reg->bank_sel, 2, tmp))
return -1;
if (i2c_write(st.hw->addr, st.reg->mem_r_w, length, data))
return -1;
return 0;
}
/**
* @brief 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.
* @param[in] mem_addr Memory location (bank << 8 | start address)
* @param[in] length Number of bytes to read.
* @param[out] data Bytes read from memory.
* @return 0 if successful.
*/
int mpu_read_mem(unsigned short mem_addr, unsigned short length,
unsigned char *data)
{
unsigned char tmp[2];
if (!data)
return -1;
if (!st.chip_cfg.sensors)
return -1;
/* Check bank boundaries. */
if (tmp[1] + length > st.hw->bank_size)
return -1;
if (i2c_write(st.hw->addr, st.reg->bank_sel, 2, tmp))
return -1;
if (i2c_read(st.hw->addr, st.reg->mem_r_w, length, data))
return -1;
return 0;
}
/**
* @brief Load and verify DMP image.
* @param[in] length Length of DMP image.
* @param[in] firmware DMP code.
* @param[in] start_addr Starting address of DMP code memory.
* @param[in] sample_rate Fixed sampling rate used when DMP is enabled.
* @return 0 if successful.
*/
int mpu_load_firmware(unsigned short length, const unsigned char *firmware,
unsigned short start_addr, unsigned short sample_rate)
{
unsigned short ii;
unsigned short this_write;
/* Must divide evenly into st.hw->bank_size to avoid bank crossings. */
#define LOAD_CHUNK (16)
unsigned char cur[LOAD_CHUNK], tmp[2];
if (st.chip_cfg.dmp_loaded)
/* DMP should only be loaded once. */
return -1;
if (!firmware)
return -1;
for (ii = 0; ii < length; ii += this_write) {
this_write = min(LOAD_CHUNK, length - ii);
if (mpu_write_mem(ii, this_write, (unsigned char*)&firmware[ii]))
return -1;
if (mpu_read_mem(ii, this_write, cur))
return -1;
if (memcmp(firmware+ii, cur, this_write))
return -2;
}
/* Set program start address. */
tmp[0] = start_addr >> 8;
tmp[1] = start_addr & 0xFF;
if (i2c_write(st.hw->addr, st.reg->prgm_start_h, 2, tmp))
return -1;
/**
* @brief Get DMP state.
* @param[out] enabled 1 if enabled.
* @return 0 if successful.
*/
int mpu_get_dmp_state(unsigned char *enabled)
{
enabled[0] = st.chip_cfg.dmp_on;
return 0;
}
#ifdef AK89xx_SECONDARY
/* This initialization is similar to the one in ak8975.c. */
static int setup_compass(void)
{
unsigned char data[4], akm_addr;
mpu_set_bypass(1);
/* Find compass. Possible addresses range from 0x0C to 0x0F. */
for (akm_addr = 0x0C; akm_addr <= 0x0F; akm_addr++) {
int result;
result = i2c_read(akm_addr, AKM_REG_WHOAMI, 1, data);
if (!result && (data[0] == AKM_WHOAMI))
break;
}
if (akm_addr > 0x0F) {
/* TODO: Handle this case in all compass-related functions. */
log_e("Compass not found.\n");
return -1;
}
/* Set slave 1 data. */
data[0] = AKM_SINGLE_MEASUREMENT;
if (i2c_write(st.hw->addr, st.reg->s1_do, 1, data))
return -1;
/* Trigger slave 0 and slave 1 actions at each sample. */
data[0] = 0x03;
if (i2c_write(st.hw->addr, st.reg->i2c_delay_ctrl, 1, data))
return -1;
#ifdef MPU9150
/* For the MPU9150, the auxiliary I2C bus needs to be set to VDD. */
data[0] = BIT_I2C_MST_VDDIO;
if (i2c_write(st.hw->addr, st.reg->yg_offs_tc, 1, data))
return -1;
#endif
return 0;
}
#endif
/**
* @brief Read raw compass data.
* @param[out] data Raw data in hardware units.
* @param[out] timestamp Timestamp in milliseconds. Null if not needed.
* @return 0 if successful.
*/
int mpu_get_compass_reg(short *data, unsigned long *timestamp)
{
#ifdef AK89xx_SECONDARY
unsigned char tmp[9];
if (!(st.chip_cfg.sensors & INV_XYZ_COMPASS))
return -1;
#ifdef AK89xx_BYPASS
if (i2c_read(st.chip_cfg.compass_addr, AKM_REG_ST1, 8, tmp))
return -1;
tmp[8] = AKM_SINGLE_MEASUREMENT;
if (i2c_write(st.chip_cfg.compass_addr, AKM_REG_CNTL, 1, tmp+8))
return -1;
#else
if (i2c_read(st.hw->addr, st.reg->raw_compass, 8, tmp))
return -1;
#endif
#if defined AK8975_SECONDARY
/* AK8975 doesn't have the overrun error bit. */
if (!(tmp[0] & AKM_DATA_READY))
return -2;
if ((tmp[7] & AKM_OVERFLOW) || (tmp[7] & AKM_DATA_ERROR))
return -3;
#elif defined AK8963_SECONDARY
/* AK8963 doesn't have the data read error bit. */
if (!(tmp[0] & AKM_DATA_READY) || (tmp[0] & AKM_DATA_OVERRUN))
return -2;
if (tmp[7] & AKM_OVERFLOW)
return -3;
#endif
data[0] = (tmp[2] << 8) | tmp[1];
data[1] = (tmp[4] << 8) | tmp[3];
data[2] = (tmp[6] << 8) | tmp[5];
if (timestamp)
get_ms(timestamp);
return 0;
#else
return -1;
#endif
}
/**
* @brief Get the compass full-scale range.
* @param[out] fsr Current full-scale range.
* @return 0 if successful.
*/
int mpu_get_compass_fsr(unsigned short *fsr)
{
#ifdef AK89xx_SECONDARY
fsr[0] = st.hw->compass_fsr;
return 0;
#else
return -1;
#endif
}
/**
* @brief Enters LP accel motion interrupt mode.
* The behaviour of this feature is very different between the MPU6050 and the
* MPU6500. Each chip's version of this feature is explained below.
*
* \n The hardware motion threshold can be between 32mg and 8160mg in 32mg
* increments.
*
* \n Low-power accel mode supports the following frequencies:
* \n 1.25Hz, 5Hz, 20Hz, 40Hz
*
* \n MPU6500:
* \n Unlike the MPU6050 version, the hardware does not "lock in" a reference
* sample. The hardware monitors the accel data and detects any large change
* over a short period of time.
*
* \n The hardware motion threshold can be between 4mg and 1020mg in 4mg
* increments.
*
* \n MPU6500 Low-power accel mode supports the following frequencies:
* \n 1.25Hz, 2.5Hz, 5Hz, 10Hz, 20Hz, 40Hz, 80Hz, 160Hz, 320Hz, 640Hz
*
* \n\n NOTES:
* \n The driver will round down @e thresh to the nearest supported value if
* an unsupported threshold is selected.
* \n To select a fractional wake-up frequency, round down the value passed to
* @e lpa_freq.
* \n The MPU6500 does not support a delay parameter. If this function is used
* for the MPU6500, the value passed to @e time will be ignored.
* \n To disable this mode, set @e lpa_freq to zero. The driver will restore
* the previous configuration.
*
* @param[in] thresh Motion threshold in mg.
* @param[in] time Duration in milliseconds that the accel data must
* exceed @e thresh before motion is reported.
* @param[in] lpa_freq Minimum sampling rate, or zero to disable.
* @return 0 if successful.
*/
int mpu_lp_motion_interrupt(unsigned short thresh, unsigned char time,
unsigned short lpa_freq)
{
#if defined MPU6500
unsigned char data[3];
#endif
if (lpa_freq) {
#if defined MPU6500
unsigned char thresh_hw;
st.chip_cfg.int_motion_only = 1;
return 0;
#endif
} else {
/* Don't "restore" the previous state if no state has been saved. */
unsigned int ii;
char *cache_ptr = (char*)&st.chip_cfg.cache;
for (ii = 0; ii < sizeof(st.chip_cfg.cache); ii++) {
if (cache_ptr[ii] != 0)
goto lp_int_restore;
}
/* If we reach this point, motion interrupt mode hasn't been used yet. */
return -1;
}
lp_int_restore:
/* Set to invalid values to ensure no I2C writes are skipped. */
st.chip_cfg.gyro_fsr = 0xFF;
st.chip_cfg.accel_fsr = 0xFF;
st.chip_cfg.lpf = 0xFF;
st.chip_cfg.sample_rate = 0xFFFF;
st.chip_cfg.sensors = 0xFF;
st.chip_cfg.fifo_enable = 0xFF;
st.chip_cfg.clk_src = INV_CLK_PLL;
mpu_set_sensors(st.chip_cfg.cache.sensors_on);
mpu_set_gyro_fsr(st.chip_cfg.cache.gyro_fsr);
mpu_set_accel_fsr(st.chip_cfg.cache.accel_fsr);
mpu_set_lpf(st.chip_cfg.cache.lpf);
mpu_set_sample_rate(st.chip_cfg.cache.sample_rate);
mpu_configure_fifo(st.chip_cfg.cache.fifo_sensors);
if (st.chip_cfg.cache.dmp_on)
mpu_set_dmp_state(1);
//陀螺仪方向设置
static signed char gyro_orientation[9] = { 1, 0, 0,
0, 1, 0,
0, 0, 1};
//磁力计方向设置
static signed char comp_orientation[9] = { 0, 1, 0,
1, 0, 0,
0, 0,-1};
//MPU9250自测试
//返回值:0,正常
// 其他,失败
u8 run_self_test(void)
{
int result;
//char test_packet[4] = {0};
long gyro[3], accel[3];
result = mpu_run_6500_self_test(gyro, accel,0);
if (result == 0x7)
{
/* Test passed. We can trust the gyro data here, so let's push it down
* to the DMP.
*/
unsigned short accel_sens;
float gyro_sens;