Hardware drivers to communicate with sensors via I2C. More...
Classes | |
struct | chip_cfg_s |
struct | dmp_s |
struct | gyro_reg_s |
struct | gyro_state_s |
struct | hw_s |
struct | int_param_s |
struct | motion_int_cache_s |
struct | test_s |
Files | |
file | inv_mpu.h |
An I2C-based driver for Invensense gyroscopes. | |
file | inv_mpu_dmp_motion_driver.h |
DMP image and interface functions. | |
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 | ANDROID_ORIENT_LANDSCAPE (0x01) |
#define | ANDROID_ORIENT_PORTRAIT (0x00) |
#define | ANDROID_ORIENT_REVERSE_LANDSCAPE (0x03) |
#define | ANDROID_ORIENT_REVERSE_PORTRAIT (0x02) |
#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 | CFG_15 (2727) |
#define | CFG_16 (2746) |
#define | CFG_20 (2224) |
#define | CFG_23 (2745) |
#define | CFG_27 (2742) |
#define | CFG_6 (2753) |
#define | CFG_7 (1205) |
#define | CFG_8 (2718) |
#define | CFG_ANDROID_ORIENT_INT (1853) |
#define | CFG_AUTH (1035) |
#define | CFG_DR_INT (1029) |
#define | CFG_EXT_GYRO_BIAS (1189) |
#define | CFG_FIFO_ON_EVENT (2690) |
#define | CFG_FLICK_IN (2573) |
#define | CFG_GYRO_RAW_DATA (2722) |
#define | CFG_LP_QUAT (2712) |
#define | CFG_MOTION_BIAS (1208) |
#define | CGNOTICE_INTR (2620) |
#define | CPASS_BIAS_X (35 * 16 + 4) |
#define | CPASS_BIAS_Y (35 * 16 + 8) |
#define | CPASS_BIAS_Z (35 * 16 + 12) |
#define | CPASS_MTX_00 (36 * 16) |
#define | CPASS_MTX_01 (36 * 16 + 4) |
#define | CPASS_MTX_02 (36 * 16 + 8) |
#define | CPASS_MTX_10 (36 * 16 + 12) |
#define | CPASS_MTX_11 (37 * 16) |
#define | CPASS_MTX_12 (37 * 16 + 4) |
#define | CPASS_MTX_20 (37 * 16 + 8) |
#define | CPASS_MTX_21 (37 * 16 + 12) |
#define | CPASS_MTX_22 (43 * 16 + 12) |
#define | D_0_104 (104) |
#define | D_0_108 (108) |
#define | D_0_163 (163) |
#define | D_0_188 (188) |
#define | D_0_192 (192) |
#define | D_0_22 (22+512) |
#define | D_0_224 (224) |
#define | D_0_228 (228) |
#define | D_0_232 (232) |
#define | D_0_236 (236) |
#define | D_0_24 (24+512) |
#define | D_0_36 (36) |
#define | D_0_52 (52) |
#define | D_0_96 (96) |
#define | D_1_10 (256 + 10) |
#define | D_1_106 (256 + 106) |
#define | D_1_108 (256 + 108) |
#define | D_1_112 (256 + 112) |
#define | D_1_128 (256 + 144) |
#define | D_1_152 (256 + 12) |
#define | D_1_160 (256 + 160) |
#define | D_1_176 (256 + 176) |
#define | D_1_178 (256 + 178) |
#define | D_1_2 (256 + 2) |
#define | D_1_218 (256 + 218) |
#define | D_1_232 (256 + 232) |
#define | D_1_236 (256 + 236) |
#define | D_1_24 (256 + 24) |
#define | D_1_240 (256 + 240) |
#define | D_1_244 (256 + 244) |
#define | D_1_250 (256 + 250) |
#define | D_1_252 (256 + 252) |
#define | D_1_28 (256 + 28) |
#define | D_1_36 (256 + 36) |
#define | D_1_4 (256 + 4) |
#define | D_1_40 (256 + 40) |
#define | D_1_44 (256 + 44) |
#define | D_1_72 (256 + 72) |
#define | D_1_74 (256 + 74) |
#define | D_1_79 (256 + 79) |
#define | D_1_8 (256 + 8) |
#define | D_1_88 (256 + 88) |
#define | D_1_90 (256 + 90) |
#define | D_1_92 (256 + 92) |
#define | D_1_96 (256 + 96) |
#define | D_1_98 (256 + 98) |
#define | D_2_108 (512 + 108) |
#define | D_2_12 (512 + 12) |
#define | D_2_208 (512 + 208) |
#define | D_2_224 (512 + 224) |
#define | D_2_236 (512 + 236) |
#define | D_2_244 (512 + 244) |
#define | D_2_248 (512 + 248) |
#define | D_2_252 (512 + 252) |
#define | D_2_96 (512 + 96) |
#define | D_ACCEL_BIAS (660) |
#define | D_ACSX (40 * 16 + 4) |
#define | D_ACSY (40 * 16 + 8) |
#define | D_ACSZ (40 * 16 + 12) |
#define | D_ACT0 (40 * 16) |
#define | D_AUTH_A (1000) |
#define | D_AUTH_B (1004) |
#define | D_AUTH_IN (996) |
#define | D_AUTH_OUT (992) |
#define | D_EXT_GYRO_BIAS_X (61 * 16) |
#define | D_EXT_GYRO_BIAS_Y (61 * 16) + 4 |
#define | D_EXT_GYRO_BIAS_Z (61 * 16) + 8 |
#define | D_HOST_NO_MOT (976) |
#define | D_ORIENT_GAP (76) |
#define | D_PEDSTD_BP_A1 (768 + 0x4C) |
#define | D_PEDSTD_BP_A2 (768 + 0x48) |
#define | D_PEDSTD_BP_A3 (768 + 0x44) |
#define | D_PEDSTD_BP_A4 (768 + 0x40) |
#define | D_PEDSTD_BP_B (768 + 0x1C) |
#define | D_PEDSTD_CLIP (768 + 0x6C) |
#define | D_PEDSTD_DECI (768 + 0xA0) |
#define | D_PEDSTD_HP_A (768 + 0x78) |
#define | D_PEDSTD_HP_B (768 + 0x7C) |
#define | D_PEDSTD_INT_THRSH (768 + 0x68) |
#define | D_PEDSTD_PEAK (768 + 0X94) |
#define | D_PEDSTD_PEAKTHRSH (768 + 0x98) |
#define | D_PEDSTD_SB (768 + 0x28) |
#define | D_PEDSTD_SB_TIME (768 + 0x2C) |
#define | D_PEDSTD_STEPCTR (768 + 0x60) |
#define | D_PEDSTD_TIMECTR (964) |
#define | D_PEDSTD_TIMH (768 + 0x2E) |
#define | D_PEDSTD_TIML (768 + 0x2A) |
#define | D_TILT0_H (48) |
#define | D_TILT0_L (50) |
#define | D_TILT1_H (52) |
#define | D_TILT1_L (54) |
#define | D_TILT2_H (56) |
#define | D_TILT2_L (58) |
#define | D_TILT3_H (60) |
#define | D_TILT3_L (62) |
#define | delay_ms delay |
#define | delay_ms delay |
#define | DMP_CODE_SIZE (3062) |
#define | DMP_FEATURE_6X_LP_QUAT (0x010) |
#define | DMP_FEATURE_ANDROID_ORIENT (0x002) |
#define | DMP_FEATURE_GYRO_CAL (0x020) |
#define | DMP_FEATURE_LP_QUAT (0x004) |
#define | DMP_FEATURE_PEDOMETER (0x008) |
#define | DMP_FEATURE_SEND_ANY_GYRO |
#define | DMP_FEATURE_SEND_CAL_GYRO (0x100) |
#define | DMP_FEATURE_SEND_RAW_ACCEL (0x040) |
#define | DMP_FEATURE_SEND_RAW_GYRO (0x080) |
#define | DMP_FEATURE_TAP (0x001) |
#define | DMP_INT_CONTINUOUS (0x02) |
#define | DMP_INT_GESTURE (0x01) |
#define | DMP_SAMPLE_RATE (200) |
#define | DO_NOT_UPDATE_PROP_ROT (1839) |
#define | END_COMPARE_Y_X (1484) |
#define | END_COMPARE_Y_X_TMP (1407) |
#define | END_COMPARE_Y_X_TMP2 (1455) |
#define | END_COMPARE_Y_X_TMP3 (1434) |
#define | END_ORIENT (1884) |
#define | END_ORIENT_TEMP (1866) |
#define | END_PREDICTION_UPDATE (1761) |
#define | FCFG_1 (1062) |
#define | FCFG_2 (1066) |
#define | FCFG_3 (1088) |
#define | FCFG_6 (1106) |
#define | FCFG_7 (1073) |
#define | FIFO_CORRUPTION_CHECK |
#define | FLAT_STATE_END (1713) |
#define | FLAT_STATE_END_TEMP (1683) |
#define | FLICK_COUNTER (45 * 16 + 8) |
#define | FLICK_LOWER (45 * 16 + 12) |
#define | FLICK_MSG (45 * 16 + 4) |
#define | FLICK_UPPER (46 * 16 + 12) |
#define | GYRO_SF (46850825LL * 200 / DMP_SAMPLE_RATE) |
#define | i2c_read !I2Cdev::readBytes |
#define | i2c_write !I2Cdev::writeBytes |
#define | INT_SRC_ANDROID_ORIENT (0x08) |
#define | INT_SRC_TAP (0x01) |
#define | INV_WXYZ_QUAT (0x100) |
#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 | log_e(...) do {} while (0) |
#define | log_i(...) do {} while (0) |
#define | MAX_COMPASS_SAMPLE_RATE (100) |
#define | MAX_PACKET_LENGTH (32) |
#define | MAX_PACKET_LENGTH (12) |
#define | min(a, b) ((a<b)?a:b) |
#define | MPU6050 |
#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 |
#define | QUAT_ERROR_THRESH (1L<<24) |
#define | QUAT_MAG_SQ_MAX (QUAT_MAG_SQ_NORMALIZED + QUAT_ERROR_THRESH) |
#define | QUAT_MAG_SQ_MIN (QUAT_MAG_SQ_NORMALIZED - QUAT_ERROR_THRESH) |
#define | QUAT_MAG_SQ_NORMALIZED (1L<<28) |
#define | SKIP_END_COMPARE (1435) |
#define | SKIP_SWING_END_1 (1551) |
#define | SKIP_SWING_END_2 (1566) |
#define | SKIP_SWING_END_3 (1588) |
#define | SKIP_X_GRT_Y_TMP (1359) |
#define | SUPPORTS_AK89xx_HIGH_SENS (0x00) |
#define | SWING_END_1 (1550) |
#define | SWING_END_2 (1565) |
#define | SWING_END_3 (1587) |
#define | SWING_END_4 (1616) |
#define | TAP_X (0x01) |
#define | TAP_X_DOWN (0x02) |
#define | TAP_X_UP (0x01) |
#define | TAP_XYZ (0x07) |
#define | TAP_Y (0x02) |
#define | TAP_Y_DOWN (0x04) |
#define | TAP_Y_UP (0x03) |
#define | TAP_Z (0x04) |
#define | TAP_Z_DOWN (0x06) |
#define | TAP_Z_UP (0x05) |
#define | TEMPLABEL (2324) |
#define | TILTG75_START (1672) |
#define | TILTL75_END (1669) |
#define | TILTL75_START (1643) |
#define | UPDATE_PROP_ROT (1835) |
#define | X_GRT_Y (1408) |
#define | X_GRT_Y_TMP (1358) |
#define | X_GRT_Y_TMP2 (1379) |
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 | dmp_enable_6x_lp_quat (unsigned char enable) |
Generate 6-axis quaternions from the dmp-> In this driver, the 3-axis and 6-axis DMP quaternion features are mutually exclusive. | |
int | dmp_enable_feature (unsigned short mask) |
Enable DMP features. The following #define's are used in the input mask: DMP_FEATURE_TAP DMP_FEATURE_ANDROID_ORIENT DMP_FEATURE_LP_QUAT DMP_FEATURE_6X_LP_QUAT DMP_FEATURE_GYRO_CAL DMP_FEATURE_SEND_RAW_ACCEL DMP_FEATURE_SEND_RAW_GYRO NOTE: DMP_FEATURE_LP_QUAT and DMP_FEATURE_6X_LP_QUAT are mutually exclusive. NOTE: DMP_FEATURE_SEND_RAW_GYRO and DMP_FEATURE_SEND_CAL_GYRO are also mutually exclusive. | |
int | dmp_enable_gyro_cal (unsigned char enable) |
Calibrate the gyro data in the dmp-> After eight seconds of no motion, the DMP will compute gyro biases and subtract them from the quaternion output. If dmp_enable_feature is called with DMP_FEATURE_SEND_CAL_GYRO, the biases will also be subtracted from the gyro output. | |
int | dmp_enable_lp_quat (unsigned char enable) |
Generate 3-axis quaternions from the dmp-> In this driver, the 3-axis and 6-axis DMP quaternion features are mutually exclusive. | |
int | dmp_get_enabled_features (unsigned short *mask) |
Get list of currently enabled DMP features. | |
int | dmp_get_fifo_rate (unsigned short *rate) |
Get DMP output rate. | |
void | dmp_init_structures () |
int | dmp_load_motion_driver_firmware (void) |
Load the DMP with this image. | |
int | dmp_read_fifo (short *gyro, short *accel, long *quat, unsigned long *timestamp, short *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 INV_WXYZ_QUAT 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 | dmp_select_device (int device) |
int | dmp_set_accel_bias (long *bias) |
Push accel biases to the dmp-> These biases will be removed from the DMP 6-axis quaternion. | |
int | dmp_set_fifo_rate (unsigned short rate) |
Set DMP output rate. Only used when DMP is on. | |
int | dmp_set_gyro_bias (long *bias) |
Push gyro biases to the dmp-> Because the gyro integration is handled in the DMP, any gyro biases calculated by the MPL should be pushed down to DMP memory to remove 3-axis quaternion drift. NOTE: If the DMP-based gyro calibration is enabled, the DMP will overwrite the biases written to this location once a new one is computed. | |
int | dmp_set_interrupt_mode (unsigned char mode) |
Specify when a DMP interrupt should occur. A DMP interrupt can be configured to trigger on either of the two conditions below: a. One FIFO period has elapsed (set by mpu_set_sample_rate). b. A tap event has been detected. | |
int | dmp_set_orientation (unsigned short orient) |
Push gyro and accel orientation to the dmp-> The orientation is represented here as the output of inv_orientation_matrix_to_scalar. | |
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. | |
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 | |
unsigned char | int_param_s::active_low |
void(* | int_param_s::cb )(void) |
static int | deviceIndex = 0 |
static int | deviceIndex = 0 |
struct dmp_s * | dmp |
struct dmp_s | dmpArray [MPU_MAX_DEVICES] |
struct gyro_state_s | gyroArray [MPU_MAX_DEVICES] |
struct hw_s * | hw |
struct hw_s | hwArray [MPU_MAX_DEVICES] |
unsigned char | int_param_s::lp_exit |
unsigned short | int_param_s::pin |
const unsigned char dmp_memory[DMP_CODE_SIZE] | PROGMEM |
struct gyro_reg_s * | reg |
struct gyro_reg_s | regArray [MPU_MAX_DEVICES] |
static const unsigned short | sStartAddress = 0x0400 |
struct gyro_state_s * | st |
struct test_s * | test |
struct test_s | testArray [MPU_MAX_DEVICES] |
Hardware drivers to communicate with sensors via I2C.
#define AK8975_SECONDARY |
Definition at line 71 of file inv_mpu.cpp.
#define AK89xx_FSR (9830) |
Definition at line 348 of file inv_mpu.cpp.
#define AK89xx_SECONDARY |
Definition at line 85 of file inv_mpu.cpp.
#define AKM_BIT_SELF_TEST (0x40) |
Definition at line 372 of file inv_mpu.cpp.
#define AKM_DATA_ERROR (0x40) |
Definition at line 370 of file inv_mpu.cpp.
#define AKM_DATA_OVERRUN (0x02) |
Definition at line 368 of file inv_mpu.cpp.
#define AKM_DATA_READY (0x01) |
Definition at line 367 of file inv_mpu.cpp.
#define AKM_FUSE_ROM_ACCESS (0x0F | SUPPORTS_AK89xx_HIGH_SENS) |
Definition at line 376 of file inv_mpu.cpp.
#define AKM_MODE_SELF_TEST (0x08 | SUPPORTS_AK89xx_HIGH_SENS) |
Definition at line 377 of file inv_mpu.cpp.
#define AKM_OVERFLOW (0x80) |
Definition at line 369 of file inv_mpu.cpp.
#define AKM_POWER_DOWN (0x00 | SUPPORTS_AK89xx_HIGH_SENS) |
Definition at line 374 of file inv_mpu.cpp.
#define AKM_REG_ASAX (0x10) |
Definition at line 363 of file inv_mpu.cpp.
#define AKM_REG_ASAY (0x11) |
Definition at line 364 of file inv_mpu.cpp.
#define AKM_REG_ASAZ (0x12) |
Definition at line 365 of file inv_mpu.cpp.
#define AKM_REG_ASTC (0x0C) |
Definition at line 362 of file inv_mpu.cpp.
#define AKM_REG_CNTL (0x0A) |
Definition at line 361 of file inv_mpu.cpp.
#define AKM_REG_HXL (0x03) |
Definition at line 358 of file inv_mpu.cpp.
#define AKM_REG_ST1 (0x02) |
Definition at line 357 of file inv_mpu.cpp.
#define AKM_REG_ST2 (0x09) |
Definition at line 359 of file inv_mpu.cpp.
#define AKM_REG_WHOAMI (0x00) |
Definition at line 355 of file inv_mpu.cpp.
#define AKM_SINGLE_MEASUREMENT (0x01 | SUPPORTS_AK89xx_HIGH_SENS) |
Definition at line 375 of file inv_mpu.cpp.
#define AKM_WHOAMI (0x48) |
Definition at line 379 of file inv_mpu.cpp.
#define ANDROID_ORIENT_LANDSCAPE (0x01) |
Definition at line 33 of file inv_mpu_dmp_motion_driver.h.
#define ANDROID_ORIENT_PORTRAIT (0x00) |
Definition at line 32 of file inv_mpu_dmp_motion_driver.h.
#define ANDROID_ORIENT_REVERSE_LANDSCAPE (0x03) |
Definition at line 35 of file inv_mpu_dmp_motion_driver.h.
#define ANDROID_ORIENT_REVERSE_PORTRAIT (0x02) |
Definition at line 34 of file inv_mpu_dmp_motion_driver.h.
#define BIT_ACTL (0x80) |
Definition at line 331 of file inv_mpu.cpp.
#define BIT_ANY_RD_CLR (0x10) |
Definition at line 333 of file inv_mpu.cpp.
#define BIT_AUX_IF_EN (0x20) |
Definition at line 330 of file inv_mpu.cpp.
#define BIT_BYPASS_EN (0x02) |
Definition at line 334 of file inv_mpu.cpp.
#define BIT_DATA_RDY_EN (0x01) |
Definition at line 310 of file inv_mpu.cpp.
#define BIT_DMP_EN (0x80) |
Definition at line 306 of file inv_mpu.cpp.
#define BIT_DMP_INT_EN (0x02) |
Definition at line 311 of file inv_mpu.cpp.
#define BIT_DMP_RST (0x08) |
Definition at line 308 of file inv_mpu.cpp.
#define BIT_FIFO_EN (0x40) |
Definition at line 305 of file inv_mpu.cpp.
#define BIT_FIFO_OVERFLOW (0x10) |
Definition at line 309 of file inv_mpu.cpp.
#define BIT_FIFO_RST (0x04) |
Definition at line 307 of file inv_mpu.cpp.
#define BIT_FIFO_SIZE_1024 (0x40) |
Definition at line 317 of file inv_mpu.cpp.
#define BIT_FIFO_SIZE_2048 (0x80) |
Definition at line 318 of file inv_mpu.cpp.
#define BIT_FIFO_SIZE_4096 (0xC0) |
Definition at line 319 of file inv_mpu.cpp.
#define BIT_I2C_MST_VDDIO (0x80) |
Definition at line 304 of file inv_mpu.cpp.
#define BIT_I2C_READ (0x80) |
Definition at line 328 of file inv_mpu.cpp.
#define BIT_LATCH_EN (0x20) |
Definition at line 332 of file inv_mpu.cpp.
#define BIT_LPA_CYCLE (0x20) |
Definition at line 336 of file inv_mpu.cpp.
#define BIT_MOT_INT_EN (0x40) |
Definition at line 312 of file inv_mpu.cpp.
#define BIT_RESET (0x80) |
Definition at line 320 of file inv_mpu.cpp.
#define BIT_S0_DELAY_EN (0x01) |
Definition at line 322 of file inv_mpu.cpp.
#define BIT_S2_DELAY_EN (0x04) |
Definition at line 323 of file inv_mpu.cpp.
#define BIT_SLAVE_BYTE_SW (0x40) |
Definition at line 325 of file inv_mpu.cpp.
#define BIT_SLAVE_EN (0x80) |
Definition at line 327 of file inv_mpu.cpp.
#define BIT_SLAVE_GROUP (0x10) |
Definition at line 326 of file inv_mpu.cpp.
#define BIT_SLEEP (0x40) |
Definition at line 321 of file inv_mpu.cpp.
#define BIT_STBY_XA (0x20) |
Definition at line 337 of file inv_mpu.cpp.
#define BIT_STBY_XG (0x04) |
Definition at line 340 of file inv_mpu.cpp.
#define BIT_STBY_XYZA (BIT_STBY_XA | BIT_STBY_YA | BIT_STBY_ZA) |
Definition at line 343 of file inv_mpu.cpp.
#define BIT_STBY_XYZG (BIT_STBY_XG | BIT_STBY_YG | BIT_STBY_ZG) |
Definition at line 344 of file inv_mpu.cpp.
#define BIT_STBY_YA (0x10) |
Definition at line 338 of file inv_mpu.cpp.
#define BIT_STBY_YG (0x02) |
Definition at line 341 of file inv_mpu.cpp.
#define BIT_STBY_ZA (0x08) |
Definition at line 339 of file inv_mpu.cpp.
#define BIT_STBY_ZG (0x01) |
Definition at line 342 of file inv_mpu.cpp.
#define BITS_CLK (0x07) |
Definition at line 316 of file inv_mpu.cpp.
#define BITS_FSR (0x18) |
Definition at line 313 of file inv_mpu.cpp.
#define BITS_HPF (0x07) |
Definition at line 315 of file inv_mpu.cpp.
#define BITS_I2C_MASTER_DLY (0x1F) |
Definition at line 329 of file inv_mpu.cpp.
#define BITS_LPF (0x07) |
Definition at line 314 of file inv_mpu.cpp.
#define BITS_SLAVE_LENGTH (0x0F) |
Definition at line 324 of file inv_mpu.cpp.
#define BITS_WOM_EN (0xC0) |
Definition at line 335 of file inv_mpu.cpp.
#define CFG_15 (2727) |
Definition at line 73 of file inv_mpu_dmp_motion_driver.cpp.
#define CFG_16 (2746) |
Definition at line 74 of file inv_mpu_dmp_motion_driver.cpp.
#define CFG_20 (2224) |
Definition at line 49 of file inv_mpu_dmp_motion_driver.cpp.
#define CFG_23 (2745) |
Definition at line 50 of file inv_mpu_dmp_motion_driver.cpp.
#define CFG_27 (2742) |
Definition at line 48 of file inv_mpu_dmp_motion_driver.cpp.
#define CFG_6 (2753) |
Definition at line 85 of file inv_mpu_dmp_motion_driver.cpp.
#define CFG_7 (1205) |
Definition at line 78 of file inv_mpu_dmp_motion_driver.cpp.
#define CFG_8 (2718) |
Definition at line 72 of file inv_mpu_dmp_motion_driver.cpp.
#define CFG_ANDROID_ORIENT_INT (1853) |
Definition at line 93 of file inv_mpu_dmp_motion_driver.cpp.
#define CFG_AUTH (1035) |
Definition at line 56 of file inv_mpu_dmp_motion_driver.cpp.
#define CFG_DR_INT (1029) |
Definition at line 55 of file inv_mpu_dmp_motion_driver.cpp.
#define CFG_EXT_GYRO_BIAS (1189) |
Definition at line 75 of file inv_mpu_dmp_motion_driver.cpp.
#define CFG_FIFO_ON_EVENT (2690) |
Definition at line 51 of file inv_mpu_dmp_motion_driver.cpp.
#define CFG_FLICK_IN (2573) |
Definition at line 88 of file inv_mpu_dmp_motion_driver.cpp.
#define CFG_GYRO_RAW_DATA (2722) |
Definition at line 94 of file inv_mpu_dmp_motion_driver.cpp.
#define CFG_LP_QUAT (2712) |
Definition at line 46 of file inv_mpu_dmp_motion_driver.cpp.
#define CFG_MOTION_BIAS (1208) |
Definition at line 90 of file inv_mpu_dmp_motion_driver.cpp.
#define CGNOTICE_INTR (2620) |
Definition at line 53 of file inv_mpu_dmp_motion_driver.cpp.
#define CPASS_BIAS_X (35 * 16 + 4) |
Definition at line 155 of file inv_mpu_dmp_motion_driver.cpp.
#define CPASS_BIAS_Y (35 * 16 + 8) |
Definition at line 156 of file inv_mpu_dmp_motion_driver.cpp.
#define CPASS_BIAS_Z (35 * 16 + 12) |
Definition at line 157 of file inv_mpu_dmp_motion_driver.cpp.
#define CPASS_MTX_00 (36 * 16) |
Definition at line 158 of file inv_mpu_dmp_motion_driver.cpp.
#define CPASS_MTX_01 (36 * 16 + 4) |
Definition at line 159 of file inv_mpu_dmp_motion_driver.cpp.
#define CPASS_MTX_02 (36 * 16 + 8) |
Definition at line 160 of file inv_mpu_dmp_motion_driver.cpp.
#define CPASS_MTX_10 (36 * 16 + 12) |
Definition at line 161 of file inv_mpu_dmp_motion_driver.cpp.
#define CPASS_MTX_11 (37 * 16) |
Definition at line 162 of file inv_mpu_dmp_motion_driver.cpp.
#define CPASS_MTX_12 (37 * 16 + 4) |
Definition at line 163 of file inv_mpu_dmp_motion_driver.cpp.
#define CPASS_MTX_20 (37 * 16 + 8) |
Definition at line 164 of file inv_mpu_dmp_motion_driver.cpp.
#define CPASS_MTX_21 (37 * 16 + 12) |
Definition at line 165 of file inv_mpu_dmp_motion_driver.cpp.
#define CPASS_MTX_22 (43 * 16 + 12) |
Definition at line 166 of file inv_mpu_dmp_motion_driver.cpp.
#define D_0_104 (104) |
Definition at line 103 of file inv_mpu_dmp_motion_driver.cpp.
#define D_0_108 (108) |
Definition at line 104 of file inv_mpu_dmp_motion_driver.cpp.
#define D_0_163 (163) |
Definition at line 105 of file inv_mpu_dmp_motion_driver.cpp.
#define D_0_188 (188) |
Definition at line 106 of file inv_mpu_dmp_motion_driver.cpp.
#define D_0_192 (192) |
Definition at line 107 of file inv_mpu_dmp_motion_driver.cpp.
#define D_0_22 (22+512) |
Definition at line 97 of file inv_mpu_dmp_motion_driver.cpp.
#define D_0_224 (224) |
Definition at line 108 of file inv_mpu_dmp_motion_driver.cpp.
#define D_0_228 (228) |
Definition at line 109 of file inv_mpu_dmp_motion_driver.cpp.
#define D_0_232 (232) |
Definition at line 110 of file inv_mpu_dmp_motion_driver.cpp.
#define D_0_236 (236) |
Definition at line 111 of file inv_mpu_dmp_motion_driver.cpp.
#define D_0_24 (24+512) |
Definition at line 98 of file inv_mpu_dmp_motion_driver.cpp.
#define D_0_36 (36) |
Definition at line 100 of file inv_mpu_dmp_motion_driver.cpp.
#define D_0_52 (52) |
Definition at line 101 of file inv_mpu_dmp_motion_driver.cpp.
#define D_0_96 (96) |
Definition at line 102 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_10 (256 + 10) |
Definition at line 116 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_106 (256 + 106) |
Definition at line 130 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_108 (256 + 108) |
Definition at line 131 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_112 (256 + 112) |
Definition at line 132 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_128 (256 + 144) |
Definition at line 133 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_152 (256 + 12) |
Definition at line 134 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_160 (256 + 160) |
Definition at line 135 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_176 (256 + 176) |
Definition at line 136 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_178 (256 + 178) |
Definition at line 137 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_2 (256 + 2) |
Definition at line 113 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_218 (256 + 218) |
Definition at line 138 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_232 (256 + 232) |
Definition at line 139 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_236 (256 + 236) |
Definition at line 140 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_24 (256 + 24) |
Definition at line 117 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_240 (256 + 240) |
Definition at line 141 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_244 (256 + 244) |
Definition at line 142 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_250 (256 + 250) |
Definition at line 143 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_252 (256 + 252) |
Definition at line 144 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_28 (256 + 28) |
Definition at line 118 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_36 (256 + 36) |
Definition at line 119 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_4 (256 + 4) |
Definition at line 114 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_40 (256 + 40) |
Definition at line 120 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_44 (256 + 44) |
Definition at line 121 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_72 (256 + 72) |
Definition at line 122 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_74 (256 + 74) |
Definition at line 123 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_79 (256 + 79) |
Definition at line 124 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_8 (256 + 8) |
Definition at line 115 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_88 (256 + 88) |
Definition at line 125 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_90 (256 + 90) |
Definition at line 126 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_92 (256 + 92) |
Definition at line 127 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_96 (256 + 96) |
Definition at line 128 of file inv_mpu_dmp_motion_driver.cpp.
#define D_1_98 (256 + 98) |
Definition at line 129 of file inv_mpu_dmp_motion_driver.cpp.
#define D_2_108 (512 + 108) |
Definition at line 147 of file inv_mpu_dmp_motion_driver.cpp.
#define D_2_12 (512 + 12) |
Definition at line 145 of file inv_mpu_dmp_motion_driver.cpp.
#define D_2_208 (512 + 208) |
Definition at line 148 of file inv_mpu_dmp_motion_driver.cpp.
#define D_2_224 (512 + 224) |
Definition at line 149 of file inv_mpu_dmp_motion_driver.cpp.
#define D_2_236 (512 + 236) |
Definition at line 150 of file inv_mpu_dmp_motion_driver.cpp.
#define D_2_244 (512 + 244) |
Definition at line 151 of file inv_mpu_dmp_motion_driver.cpp.
#define D_2_248 (512 + 248) |
Definition at line 152 of file inv_mpu_dmp_motion_driver.cpp.
#define D_2_252 (512 + 252) |
Definition at line 153 of file inv_mpu_dmp_motion_driver.cpp.
#define D_2_96 (512 + 96) |
Definition at line 146 of file inv_mpu_dmp_motion_driver.cpp.
#define D_ACCEL_BIAS (660) |
Definition at line 205 of file inv_mpu_dmp_motion_driver.cpp.
#define D_ACSX (40 * 16 + 4) |
Definition at line 171 of file inv_mpu_dmp_motion_driver.cpp.
#define D_ACSY (40 * 16 + 8) |
Definition at line 172 of file inv_mpu_dmp_motion_driver.cpp.
#define D_ACSZ (40 * 16 + 12) |
Definition at line 173 of file inv_mpu_dmp_motion_driver.cpp.
#define D_ACT0 (40 * 16) |
Definition at line 170 of file inv_mpu_dmp_motion_driver.cpp.
#define D_AUTH_A (1000) |
Definition at line 182 of file inv_mpu_dmp_motion_driver.cpp.
#define D_AUTH_B (1004) |
Definition at line 183 of file inv_mpu_dmp_motion_driver.cpp.
#define D_AUTH_IN (996) |
Definition at line 181 of file inv_mpu_dmp_motion_driver.cpp.
#define D_AUTH_OUT (992) |
Definition at line 180 of file inv_mpu_dmp_motion_driver.cpp.
#define D_EXT_GYRO_BIAS_X (61 * 16) |
Definition at line 167 of file inv_mpu_dmp_motion_driver.cpp.
#define D_EXT_GYRO_BIAS_Y (61 * 16) + 4 |
Definition at line 168 of file inv_mpu_dmp_motion_driver.cpp.
#define D_EXT_GYRO_BIAS_Z (61 * 16) + 8 |
Definition at line 169 of file inv_mpu_dmp_motion_driver.cpp.
#define D_HOST_NO_MOT (976) |
Definition at line 204 of file inv_mpu_dmp_motion_driver.cpp.
#define D_ORIENT_GAP (76) |
Definition at line 207 of file inv_mpu_dmp_motion_driver.cpp.
#define D_PEDSTD_BP_A1 (768 + 0x4C) |
Definition at line 191 of file inv_mpu_dmp_motion_driver.cpp.
#define D_PEDSTD_BP_A2 (768 + 0x48) |
Definition at line 190 of file inv_mpu_dmp_motion_driver.cpp.
#define D_PEDSTD_BP_A3 (768 + 0x44) |
Definition at line 189 of file inv_mpu_dmp_motion_driver.cpp.
#define D_PEDSTD_BP_A4 (768 + 0x40) |
Definition at line 188 of file inv_mpu_dmp_motion_driver.cpp.
#define D_PEDSTD_BP_B (768 + 0x1C) |
Definition at line 185 of file inv_mpu_dmp_motion_driver.cpp.
#define D_PEDSTD_CLIP (768 + 0x6C) |
Definition at line 193 of file inv_mpu_dmp_motion_driver.cpp.
#define D_PEDSTD_DECI (768 + 0xA0) |
Definition at line 202 of file inv_mpu_dmp_motion_driver.cpp.
#define D_PEDSTD_HP_A (768 + 0x78) |
Definition at line 186 of file inv_mpu_dmp_motion_driver.cpp.
#define D_PEDSTD_HP_B (768 + 0x7C) |
Definition at line 187 of file inv_mpu_dmp_motion_driver.cpp.
#define D_PEDSTD_INT_THRSH (768 + 0x68) |
Definition at line 192 of file inv_mpu_dmp_motion_driver.cpp.
#define D_PEDSTD_PEAK (768 + 0X94) |
Definition at line 199 of file inv_mpu_dmp_motion_driver.cpp.
#define D_PEDSTD_PEAKTHRSH (768 + 0x98) |
Definition at line 196 of file inv_mpu_dmp_motion_driver.cpp.
#define D_PEDSTD_SB (768 + 0x28) |
Definition at line 194 of file inv_mpu_dmp_motion_driver.cpp.
#define D_PEDSTD_SB_TIME (768 + 0x2C) |
Definition at line 195 of file inv_mpu_dmp_motion_driver.cpp.
#define D_PEDSTD_STEPCTR (768 + 0x60) |
Definition at line 200 of file inv_mpu_dmp_motion_driver.cpp.
#define D_PEDSTD_TIMECTR (964) |
Definition at line 201 of file inv_mpu_dmp_motion_driver.cpp.
#define D_PEDSTD_TIMH (768 + 0x2E) |
Definition at line 198 of file inv_mpu_dmp_motion_driver.cpp.
#define D_PEDSTD_TIML (768 + 0x2A) |
Definition at line 197 of file inv_mpu_dmp_motion_driver.cpp.
#define D_TILT0_H (48) |
Definition at line 209 of file inv_mpu_dmp_motion_driver.cpp.
#define D_TILT0_L (50) |
Definition at line 210 of file inv_mpu_dmp_motion_driver.cpp.
#define D_TILT1_H (52) |
Definition at line 211 of file inv_mpu_dmp_motion_driver.cpp.
#define D_TILT1_L (54) |
Definition at line 212 of file inv_mpu_dmp_motion_driver.cpp.
#define D_TILT2_H (56) |
Definition at line 213 of file inv_mpu_dmp_motion_driver.cpp.
#define D_TILT2_L (58) |
Definition at line 214 of file inv_mpu_dmp_motion_driver.cpp.
#define D_TILT3_H (60) |
Definition at line 215 of file inv_mpu_dmp_motion_driver.cpp.
#define D_TILT3_L (62) |
Definition at line 216 of file inv_mpu_dmp_motion_driver.cpp.
#define delay_ms delay |
Definition at line 36 of file inv_mpu_dmp_motion_driver.cpp.
#define delay_ms delay |
Definition at line 42 of file inv_mpu.cpp.
#define DMP_CODE_SIZE (3062) |
Definition at line 218 of file inv_mpu_dmp_motion_driver.cpp.
#define DMP_FEATURE_6X_LP_QUAT (0x010) |
Definition at line 44 of file inv_mpu_dmp_motion_driver.h.
#define DMP_FEATURE_ANDROID_ORIENT (0x002) |
Definition at line 41 of file inv_mpu_dmp_motion_driver.h.
#define DMP_FEATURE_GYRO_CAL (0x020) |
Definition at line 45 of file inv_mpu_dmp_motion_driver.h.
#define DMP_FEATURE_LP_QUAT (0x004) |
Definition at line 42 of file inv_mpu_dmp_motion_driver.h.
#define DMP_FEATURE_PEDOMETER (0x008) |
Definition at line 43 of file inv_mpu_dmp_motion_driver.h.
#define DMP_FEATURE_SEND_ANY_GYRO |
(DMP_FEATURE_SEND_RAW_GYRO | \ DMP_FEATURE_SEND_CAL_GYRO)
Definition at line 439 of file inv_mpu_dmp_motion_driver.cpp.
#define DMP_FEATURE_SEND_CAL_GYRO (0x100) |
Definition at line 48 of file inv_mpu_dmp_motion_driver.h.
#define DMP_FEATURE_SEND_RAW_ACCEL (0x040) |
Definition at line 46 of file inv_mpu_dmp_motion_driver.h.
#define DMP_FEATURE_SEND_RAW_GYRO (0x080) |
Definition at line 47 of file inv_mpu_dmp_motion_driver.h.
#define DMP_FEATURE_TAP (0x001) |
Definition at line 40 of file inv_mpu_dmp_motion_driver.h.
#define DMP_INT_CONTINUOUS (0x02) |
Definition at line 38 of file inv_mpu_dmp_motion_driver.h.
#define DMP_INT_GESTURE (0x01) |
Definition at line 37 of file inv_mpu_dmp_motion_driver.h.
#define DMP_SAMPLE_RATE (200) |
Definition at line 444 of file inv_mpu_dmp_motion_driver.cpp.
#define DO_NOT_UPDATE_PROP_ROT (1839) |
Definition at line 77 of file inv_mpu_dmp_motion_driver.cpp.
#define END_COMPARE_Y_X (1484) |
Definition at line 80 of file inv_mpu_dmp_motion_driver.cpp.
#define END_COMPARE_Y_X_TMP (1407) |
Definition at line 76 of file inv_mpu_dmp_motion_driver.cpp.
#define END_COMPARE_Y_X_TMP2 (1455) |
Definition at line 58 of file inv_mpu_dmp_motion_driver.cpp.
#define END_COMPARE_Y_X_TMP3 (1434) |
Definition at line 64 of file inv_mpu_dmp_motion_driver.cpp.
#define END_ORIENT (1884) |
Definition at line 87 of file inv_mpu_dmp_motion_driver.cpp.
#define END_ORIENT_TEMP (1866) |
Definition at line 47 of file inv_mpu_dmp_motion_driver.cpp.
#define END_PREDICTION_UPDATE (1761) |
Definition at line 52 of file inv_mpu_dmp_motion_driver.cpp.
#define FCFG_1 (1062) |
Definition at line 63 of file inv_mpu_dmp_motion_driver.cpp.
#define FCFG_2 (1066) |
Definition at line 62 of file inv_mpu_dmp_motion_driver.cpp.
#define FCFG_3 (1088) |
Definition at line 61 of file inv_mpu_dmp_motion_driver.cpp.
#define FCFG_6 (1106) |
Definition at line 66 of file inv_mpu_dmp_motion_driver.cpp.
#define FCFG_7 (1073) |
Definition at line 65 of file inv_mpu_dmp_motion_driver.cpp.
#define FIFO_CORRUPTION_CHECK |
Definition at line 447 of file inv_mpu_dmp_motion_driver.cpp.
#define FLAT_STATE_END (1713) |
Definition at line 67 of file inv_mpu_dmp_motion_driver.cpp.
#define FLAT_STATE_END_TEMP (1683) |
Definition at line 79 of file inv_mpu_dmp_motion_driver.cpp.
#define FLICK_COUNTER (45 * 16 + 8) |
Definition at line 176 of file inv_mpu_dmp_motion_driver.cpp.
#define FLICK_LOWER (45 * 16 + 12) |
Definition at line 177 of file inv_mpu_dmp_motion_driver.cpp.
#define FLICK_MSG (45 * 16 + 4) |
Definition at line 175 of file inv_mpu_dmp_motion_driver.cpp.
#define FLICK_UPPER (46 * 16 + 12) |
Definition at line 178 of file inv_mpu_dmp_motion_driver.cpp.
#define GYRO_SF (46850825LL * 200 / DMP_SAMPLE_RATE) |
Definition at line 445 of file inv_mpu_dmp_motion_driver.cpp.
#define i2c_read !I2Cdev::readBytes |
Definition at line 41 of file inv_mpu.cpp.
#define i2c_write !I2Cdev::writeBytes |
Definition at line 40 of file inv_mpu.cpp.
#define INT_SRC_ANDROID_ORIENT (0x08) |
Definition at line 437 of file inv_mpu_dmp_motion_driver.cpp.
#define INT_SRC_TAP (0x01) |
Definition at line 436 of file inv_mpu_dmp_motion_driver.cpp.
#define INV_WXYZ_QUAT (0x100) |
Definition at line 50 of file inv_mpu_dmp_motion_driver.h.
#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 log_e | ( | ... | ) | do {} while (0) |
Definition at line 39 of file inv_mpu_dmp_motion_driver.cpp.
#define log_i | ( | ... | ) | do {} while (0) |
Definition at line 38 of file inv_mpu_dmp_motion_driver.cpp.
#define MAX_COMPASS_SAMPLE_RATE (100) |
Definition at line 493 of file inv_mpu.cpp.
#define MAX_PACKET_LENGTH (32) |
Definition at line 442 of file inv_mpu_dmp_motion_driver.cpp.
#define MAX_PACKET_LENGTH (12) |
Definition at line 489 of file inv_mpu.cpp.
#define min | ( | a, | |
b | |||
) | ((a<b)?a:b) |
Definition at line 47 of file inv_mpu.cpp.
#define MPU6050 |
Definition at line 66 of file inv_mpu.cpp.
#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 |
#define QUAT_ERROR_THRESH (1L<<24) |
Definition at line 449 of file inv_mpu_dmp_motion_driver.cpp.
#define QUAT_MAG_SQ_MAX (QUAT_MAG_SQ_NORMALIZED + QUAT_ERROR_THRESH) |
Definition at line 452 of file inv_mpu_dmp_motion_driver.cpp.
#define QUAT_MAG_SQ_MIN (QUAT_MAG_SQ_NORMALIZED - QUAT_ERROR_THRESH) |
Definition at line 451 of file inv_mpu_dmp_motion_driver.cpp.
#define QUAT_MAG_SQ_NORMALIZED (1L<<28) |
Definition at line 450 of file inv_mpu_dmp_motion_driver.cpp.
#define SKIP_END_COMPARE (1435) |
Definition at line 60 of file inv_mpu_dmp_motion_driver.cpp.
#define SKIP_SWING_END_1 (1551) |
Definition at line 81 of file inv_mpu_dmp_motion_driver.cpp.
#define SKIP_SWING_END_2 (1566) |
Definition at line 83 of file inv_mpu_dmp_motion_driver.cpp.
#define SKIP_SWING_END_3 (1588) |
Definition at line 82 of file inv_mpu_dmp_motion_driver.cpp.
#define SKIP_X_GRT_Y_TMP (1359) |
Definition at line 59 of file inv_mpu_dmp_motion_driver.cpp.
#define SUPPORTS_AK89xx_HIGH_SENS (0x00) |
Definition at line 347 of file inv_mpu.cpp.
#define SWING_END_1 (1550) |
Definition at line 71 of file inv_mpu_dmp_motion_driver.cpp.
#define SWING_END_2 (1565) |
Definition at line 69 of file inv_mpu_dmp_motion_driver.cpp.
#define SWING_END_3 (1587) |
Definition at line 70 of file inv_mpu_dmp_motion_driver.cpp.
#define SWING_END_4 (1616) |
Definition at line 68 of file inv_mpu_dmp_motion_driver.cpp.
#define TAP_X (0x01) |
Definition at line 20 of file inv_mpu_dmp_motion_driver.h.
#define TAP_X_DOWN (0x02) |
Definition at line 26 of file inv_mpu_dmp_motion_driver.h.
#define TAP_X_UP (0x01) |
Definition at line 25 of file inv_mpu_dmp_motion_driver.h.
#define TAP_XYZ (0x07) |
Definition at line 23 of file inv_mpu_dmp_motion_driver.h.
#define TAP_Y (0x02) |
Definition at line 21 of file inv_mpu_dmp_motion_driver.h.
#define TAP_Y_DOWN (0x04) |
Definition at line 28 of file inv_mpu_dmp_motion_driver.h.
#define TAP_Y_UP (0x03) |
Definition at line 27 of file inv_mpu_dmp_motion_driver.h.
#define TAP_Z (0x04) |
Definition at line 22 of file inv_mpu_dmp_motion_driver.h.
#define TAP_Z_DOWN (0x06) |
Definition at line 30 of file inv_mpu_dmp_motion_driver.h.
#define TAP_Z_UP (0x05) |
Definition at line 29 of file inv_mpu_dmp_motion_driver.h.
#define TEMPLABEL (2324) |
Definition at line 92 of file inv_mpu_dmp_motion_driver.cpp.
#define TILTG75_START (1672) |
Definition at line 84 of file inv_mpu_dmp_motion_driver.cpp.
#define TILTL75_END (1669) |
Definition at line 86 of file inv_mpu_dmp_motion_driver.cpp.
#define TILTL75_START (1643) |
Definition at line 89 of file inv_mpu_dmp_motion_driver.cpp.
#define UPDATE_PROP_ROT (1835) |
Definition at line 57 of file inv_mpu_dmp_motion_driver.cpp.
#define X_GRT_Y (1408) |
Definition at line 91 of file inv_mpu_dmp_motion_driver.cpp.
#define X_GRT_Y_TMP (1358) |
Definition at line 54 of file inv_mpu_dmp_motion_driver.cpp.
#define X_GRT_Y_TMP2 (1379) |
Definition at line 95 of file inv_mpu_dmp_motion_driver.cpp.
enum accel_fsr_e |
Definition at line 266 of file inv_mpu.cpp.
enum clock_sel_e |
Definition at line 275 of file inv_mpu.cpp.
enum gyro_fsr_e |
Definition at line 257 of file inv_mpu.cpp.
enum lp_accel_rate_e |
Definition at line 282 of file inv_mpu.cpp.
enum lpf_e |
INV_FILTER_256HZ_NOLPF2 | |
INV_FILTER_188HZ | |
INV_FILTER_98HZ | |
INV_FILTER_42HZ | |
INV_FILTER_20HZ | |
INV_FILTER_10HZ | |
INV_FILTER_5HZ | |
INV_FILTER_2100HZ_NOLPF | |
NUM_FILTER |
Definition at line 244 of file inv_mpu.cpp.
int dmp_enable_6x_lp_quat | ( | unsigned char | enable | ) |
Generate 6-axis quaternions from the dmp-> In this driver, the 3-axis and 6-axis DMP quaternion features are mutually exclusive.
[in] | enable | 1 to enable 6-axis quaternion. |
Definition at line 1162 of file inv_mpu_dmp_motion_driver.cpp.
int dmp_enable_feature | ( | unsigned short | mask | ) |
Enable DMP features. The following #define's are used in the input mask:
DMP_FEATURE_TAP
DMP_FEATURE_ANDROID_ORIENT
DMP_FEATURE_LP_QUAT
DMP_FEATURE_6X_LP_QUAT
DMP_FEATURE_GYRO_CAL
DMP_FEATURE_SEND_RAW_ACCEL
DMP_FEATURE_SEND_RAW_GYRO
NOTE: DMP_FEATURE_LP_QUAT and DMP_FEATURE_6X_LP_QUAT are mutually exclusive.
NOTE: DMP_FEATURE_SEND_RAW_GYRO and DMP_FEATURE_SEND_CAL_GYRO are also mutually exclusive.
[in] | mask | Mask of features to enable. |
Definition at line 981 of file inv_mpu_dmp_motion_driver.cpp.
int dmp_enable_gyro_cal | ( | unsigned char | enable | ) |
Calibrate the gyro data in the dmp-> After eight seconds of no motion, the DMP will compute gyro biases and subtract them from the quaternion output. If dmp_enable_feature is called with DMP_FEATURE_SEND_CAL_GYRO, the biases will also be subtracted from the gyro output.
[in] | enable | 1 to enable gyro calibration. |
Definition at line 1120 of file inv_mpu_dmp_motion_driver.cpp.
int dmp_enable_lp_quat | ( | unsigned char | enable | ) |
Generate 3-axis quaternions from the dmp-> In this driver, the 3-axis and 6-axis DMP quaternion features are mutually exclusive.
[in] | enable | 1 to enable 3-axis quaternion. |
Definition at line 1138 of file inv_mpu_dmp_motion_driver.cpp.
int dmp_get_enabled_features | ( | unsigned short * | mask | ) |
Get list of currently enabled DMP features.
[out] | Mask | of enabled features. |
Definition at line 1105 of file inv_mpu_dmp_motion_driver.cpp.
int dmp_get_fifo_rate | ( | unsigned short * | rate | ) |
Get DMP output rate.
[out] | rate | Current fifo rate (Hz). |
Definition at line 691 of file inv_mpu_dmp_motion_driver.cpp.
void dmp_init_structures | ( | ) |
Definition at line 479 of file inv_mpu_dmp_motion_driver.cpp.
int dmp_load_motion_driver_firmware | ( | void | ) |
Load the DMP with this image.
Definition at line 493 of file inv_mpu_dmp_motion_driver.cpp.
int dmp_read_fifo | ( | short * | gyro, |
short * | accel, | ||
long * | quat, | ||
unsigned long * | timestamp, | ||
short * | 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
INV_WXYZ_QUAT
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.
[out] | gyro | Gyro data in hardware units. |
[out] | accel | Accel data in hardware units. |
[out] | quat | 3-axis quaternion data in hardware units. |
[out] | timestamp | Timestamp in milliseconds. |
[out] | sensors | Mask of sensors read from FIFO. |
[out] | more | Number of remaining packets. |
Definition at line 1256 of file inv_mpu_dmp_motion_driver.cpp.
int dmp_select_device | ( | int | device | ) |
Definition at line 469 of file inv_mpu_dmp_motion_driver.cpp.
int dmp_set_accel_bias | ( | long * | bias | ) |
Push accel biases to the dmp-> These biases will be removed from the DMP 6-axis quaternion.
[in] | bias | Accel biases in q16. |
Definition at line 613 of file inv_mpu_dmp_motion_driver.cpp.
int dmp_set_fifo_rate | ( | unsigned short | rate | ) |
Set DMP output rate. Only used when DMP is on.
[in] | rate | Desired fifo rate (Hz). |
Definition at line 665 of file inv_mpu_dmp_motion_driver.cpp.
int dmp_set_gyro_bias | ( | long * | bias | ) |
Push gyro biases to the dmp-> Because the gyro integration is handled in the DMP, any gyro biases calculated by the MPL should be pushed down to DMP memory to remove 3-axis quaternion drift.
NOTE: If the DMP-based gyro calibration is enabled, the DMP will overwrite the biases written to this location once a new one is computed.
[in] | bias | Gyro biases in q16. |
Definition at line 561 of file inv_mpu_dmp_motion_driver.cpp.
int dmp_set_interrupt_mode | ( | unsigned char | mode | ) |
Specify when a DMP interrupt should occur. A DMP interrupt can be configured to trigger on either of the two conditions below:
a. One FIFO period has elapsed (set by mpu_set_sample_rate).
b. A tap event has been detected.
[in] | mode | DMP_INT_GESTURE or DMP_INT_CONTINUOUS. |
Definition at line 1217 of file inv_mpu_dmp_motion_driver.cpp.
int dmp_set_orientation | ( | unsigned short | orient | ) |
Push gyro and accel orientation to the dmp-> The orientation is represented here as the output of inv_orientation_matrix_to_scalar.
[in] | orient | Gyro and accel orientation in body frame. |
Definition at line 506 of file inv_mpu_dmp_motion_driver.cpp.
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.
[in] | sensors | Mask of sensors to push to FIFO. |
Definition at line 1369 of file inv_mpu.cpp.
int mpu_get_accel_fsr | ( | unsigned char * | fsr | ) |
Get the accel full-scale range.
[out] | fsr | Current full-scale range. |
Definition at line 1057 of file inv_mpu.cpp.
int mpu_get_accel_reg | ( | short * | data, |
unsigned long * | timestamp | ||
) |
Read raw accel data directly from the registers.
[out] | data | Raw data in hardware units. |
[out] | timestamp | Timestamp in milliseconds. Null if not needed. |
Definition at line 834 of file inv_mpu.cpp.
int mpu_get_accel_sens | ( | unsigned short * | sens | ) |
Get accel sensitivity scale factor.
[out] | sens | Conversion from hardware units to g's. |
Definition at line 1322 of file inv_mpu.cpp.
int mpu_get_compass_fsr | ( | unsigned short * | fsr | ) |
Get the compass full-scale range.
[out] | fsr | Current full-scale range. |
Definition at line 2472 of file inv_mpu.cpp.
int mpu_get_compass_reg | ( | short * | data, |
unsigned long * | timestamp | ||
) |
Read raw compass data.
[out] | data | Raw data in hardware units. |
[out] | timestamp | Timestamp in milliseconds. Null if not needed. |
Definition at line 2419 of file inv_mpu.cpp.
int mpu_get_compass_sample_rate | ( | unsigned short * | rate | ) |
Get compass sampling rate.
[out] | rate | Current compass sampling rate (Hz). |
Definition at line 1252 of file inv_mpu.cpp.
int mpu_get_dmp_state | ( | unsigned char * | enabled | ) |
Get DMP state.
[out] | enabled | 1 if enabled. |
Definition at line 2293 of file inv_mpu.cpp.
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.
[out] | sensors | Mask of sensors in FIFO. |
Definition at line 1354 of file inv_mpu.cpp.
int mpu_get_gyro_fsr | ( | unsigned short * | fsr | ) |
Get the gyro full-scale range.
[out] | fsr | Current full-scale range. |
Definition at line 993 of file inv_mpu.cpp.
int mpu_get_gyro_reg | ( | short * | data, |
unsigned long * | timestamp | ||
) |
Read raw gyro data directly from the registers.
[out] | data | Raw data in hardware units. |
[out] | timestamp | Timestamp in milliseconds. Null if not needed. |
Definition at line 811 of file inv_mpu.cpp.
int mpu_get_gyro_sens | ( | float * | sens | ) |
Get gyro sensitivity scale factor.
[out] | sens | Conversion from hardware units to dps. |
Definition at line 1296 of file inv_mpu.cpp.
int mpu_get_int_status | ( | short * | status | ) |
Read the MPU interrupt status registers.
[out] | status | Mask of interrupt bits. |
Definition at line 1507 of file inv_mpu.cpp.
int mpu_get_lpf | ( | unsigned short * | lpf | ) |
Get the current DLPF setting.
[out] | lpf | Current LPF setting. 0 if successful. |
Definition at line 1122 of file inv_mpu.cpp.
int mpu_get_power_state | ( | unsigned char * | power_on | ) |
Get current power state.
[in] | power_on | 1 if turned on, 0 if suspended. |
Definition at line 1411 of file inv_mpu.cpp.
int mpu_get_sample_rate | ( | unsigned short * | rate | ) |
Get sampling rate.
[out] | rate | Current sampling rate (Hz). |
Definition at line 1190 of file inv_mpu.cpp.
int mpu_get_temperature | ( | long * | data, |
unsigned long * | timestamp | ||
) |
Read temperature data directly from the registers.
[out] | data | Data in q16 format. |
[out] | timestamp | Timestamp in milliseconds. Null if not needed. |
Definition at line 857 of file inv_mpu.cpp.
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.
[in] | int_param | Platform-specific parameters to interrupt API. |
Definition at line 580 of file inv_mpu.cpp.
int mpu_init_slave | ( | void | ) |
void mpu_init_structures | ( | ) |
Definition at line 408 of file inv_mpu.cpp.
int mpu_load_firmware | ( | unsigned short | length, |
const unsigned char * | firmware, | ||
unsigned short | start_addr, | ||
unsigned short | sample_rate | ||
) |
Load and verify DMP image.
[in] | length | Length of DMP image. |
[in] | firmware | DMP code. |
[in] | start_addr | Starting address of DMP code memory. |
[in] | sample_rate | Fixed sampling rate used when DMP is enabled. |
Definition at line 2177 of file inv_mpu.cpp.
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.
[in] | rate | Minimum sampling rate, or zero to disable LP accel mode. |
Definition at line 727 of file inv_mpu.cpp.
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.
MPU6050:
When this mode is first enabled, the hardware captures a single accel sample, and subsequent samples are compared with this one to determine if the device is in motion. Therefore, whenever this "locked" sample needs to be changed, this function must be called again.
The hardware motion threshold can be between 32mg and 8160mg in 32mg increments.
Low-power accel mode supports the following frequencies:
1.25Hz, 5Hz, 20Hz, 40Hz
MPU6500:
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.
The hardware motion threshold can be between 4mg and 1020mg in 4mg increments.
MPU6500 Low-power accel mode supports the following frequencies:
1.25Hz, 2.5Hz, 5Hz, 10Hz, 20Hz, 40Hz, 80Hz, 160Hz, 320Hz, 640Hz
NOTES:
The driver will round down thresh to the nearest supported value if an unsupported threshold is selected.
To select a fractional wake-up frequency, round down the value passed to lpa_freq.
The MPU6500 does not support a delay parameter. If this function is used for the MPU6500, the value passed to time will be ignored.
To disable this mode, set lpa_freq to zero. The driver will restore the previous configuration.
[in] | thresh | Motion threshold in mg. |
[in] | time | Duration in milliseconds that the accel data must exceed thresh before motion is reported. |
[in] | lpa_freq | Minimum sampling rate, or zero to disable. |
Definition at line 2526 of file inv_mpu.cpp.
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.
[out] | gyro | Gyro data in hardware units. |
[out] | accel | Accel data in hardware units. |
[out] | timestamp | Timestamp in milliseconds. |
[out] | sensors | Mask of sensors read from FIFO. |
[out] | more | Number of remaining packets. |
Definition at line 1536 of file inv_mpu.cpp.
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.
[in] | length | Length of one FIFO packet. |
[in] | data | FIFO packet. |
[in] | more | Number of remaining packets. |
Definition at line 1617 of file inv_mpu.cpp.
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.
[in] | mem_addr | Memory location (bank << 8 | start address) |
[in] | length | Number of bytes to read. |
[out] | data | Bytes read from memory. |
Definition at line 2145 of file inv_mpu.cpp.
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.
[in] | reg | Register address. |
[out] | data | Register data. |
Definition at line 557 of file inv_mpu.cpp.
int mpu_reg_dump | ( | void | ) |
int mpu_reset_fifo | ( | void | ) |
Reset FIFO read/write pointers.
Definition at line 931 of file inv_mpu.cpp.
int mpu_select_device | ( | int | device | ) |
Definition at line 395 of file inv_mpu.cpp.
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.
[in] | accel_bias | New biases. |
Definition at line 882 of file inv_mpu.cpp.
int mpu_set_accel_fsr | ( | unsigned char | fsr | ) |
Set the accel full-scale range.
[in] | fsr | Desired full-scale range. |
Definition at line 1085 of file inv_mpu.cpp.
int mpu_set_bypass | ( | unsigned char | bypass_on | ) |
Set device to bypass mode.
[in] | bypass_on | 1 to enable bypass mode. |
Definition at line 1655 of file inv_mpu.cpp.
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.
WARNING: The new rate may be different than what was requested. Call mpu_get_compass_sample_rate to check the actual setting.
[in] | rate | Desired compass sampling rate (Hz). |
Definition at line 1274 of file inv_mpu.cpp.
int mpu_set_dmp_state | ( | unsigned char | enable | ) |
Enable/disable DMP support.
[in] | enable | 1 to turn on the DMP. |
Definition at line 2254 of file inv_mpu.cpp.
int mpu_set_gyro_fsr | ( | unsigned short | fsr | ) |
Set the gyro full-scale range.
[in] | fsr | Desired full-scale range. |
Definition at line 1020 of file inv_mpu.cpp.
int mpu_set_int_latched | ( | unsigned char | enable | ) |
Enable latched interrupts. Any MPU register will clear the interrupt.
[in] | enable | 1 to enable, 0 to disable. |
Definition at line 1717 of file inv_mpu.cpp.
int mpu_set_int_level | ( | unsigned char | active_low | ) |
Set interrupt level.
[in] | active_low | 1 for active low, 0 for active high. |
Definition at line 1705 of file inv_mpu.cpp.
int mpu_set_lpf | ( | unsigned short | lpf | ) |
Set digital low pass filter. The following LPF settings are supported: 188, 98, 42, 20, 10, 5.
[in] | lpf | Desired LPF setting. |
Definition at line 1158 of file inv_mpu.cpp.
int mpu_set_sample_rate | ( | unsigned short | rate | ) |
Set sampling rate. Sampling rate must be between 4Hz and 1kHz.
[in] | rate | Desired sampling rate (Hz). |
Definition at line 1205 of file inv_mpu.cpp.
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.
[in] | sensors | Mask of sensors to wake. |
Definition at line 1430 of file inv_mpu.cpp.
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.
[in] | mem_addr | Memory location (bank << 8 | start address) |
[in] | length | Number of bytes to write. |
[in] | data | Bytes to write to memory. |
Definition at line 2112 of file inv_mpu.cpp.
static int reg_int_cb | ( | struct int_param_s * | int_param | ) | [inline, static] |
Definition at line 44 of file inv_mpu.cpp.
static int set_int_enable | ( | unsigned char | enable | ) | [static] |
Enable/disable data ready interrupt. If the DMP is on, the DMP interrupt is enabled. Otherwise, the data ready interrupt is used.
[in] | enable | 1 to enable interrupt. |
Definition at line 503 of file inv_mpu.cpp.
static int setup_compass | ( | void | ) | [static] |
Definition at line 2301 of file inv_mpu.cpp.
unsigned char int_param_s::active_low |
void(* int_param_s::cb)(void) |
int deviceIndex = 0 [static] |
Definition at line 393 of file inv_mpu.cpp.
int deviceIndex = 0 [static] |
Definition at line 467 of file inv_mpu_dmp_motion_driver.cpp.
Definition at line 466 of file inv_mpu_dmp_motion_driver.cpp.
struct dmp_s dmpArray[MPU_MAX_DEVICES] |
Definition at line 464 of file inv_mpu_dmp_motion_driver.cpp.
struct gyro_state_s gyroArray[MPU_MAX_DEVICES] |
Definition at line 385 of file inv_mpu.cpp.
Definition at line 390 of file inv_mpu.cpp.
struct hw_s hwArray[MPU_MAX_DEVICES] |
Definition at line 383 of file inv_mpu.cpp.
unsigned char int_param_s::lp_exit |
unsigned short int_param_s::pin |
const unsigned char dmp_memory [DMP_CODE_SIZE] PROGMEM |
Definition at line 223 of file inv_mpu_dmp_motion_driver.cpp.
struct gyro_reg_s* reg |
Definition at line 389 of file inv_mpu.cpp.
struct gyro_reg_s regArray[MPU_MAX_DEVICES] |
Definition at line 382 of file inv_mpu.cpp.
const unsigned short sStartAddress = 0x0400 [static] |
Definition at line 432 of file inv_mpu_dmp_motion_driver.cpp.
struct gyro_state_s* st |
Definition at line 392 of file inv_mpu.cpp.
Definition at line 391 of file inv_mpu.cpp.
struct test_s testArray[MPU_MAX_DEVICES] |
Definition at line 384 of file inv_mpu.cpp.