mpu9150: rewrite from scratch
This driver has been rewritten from scratch. It is implemented as 3 seperate drivers now (but all included as part of the mpu9150 UPM library): AK8975 (Magnetometer) MPU60X0 (Accelerometer, Gyroscope, and Temperature sensor) MPU9150 (composed of AK8975 and MPU60X0) Each driver can be used independently and includes examples in C++/JS/Python. Commonly used capabilities are supported, and methods/register definitions exist to easily implement any desired functionality that is missing. Interrupt support has also been added. Scaling support has also been properly implemented for both the Accelerometer and Gyroscope. Signed-off-by: Jon Trulson <jtrulson@ics.com> Signed-off-by: Mihai Tudor Panu <mihai.tudor.panu@intel.com>
This commit is contained in:
committed by
Mihai Tudor Panu
parent
6613dea552
commit
03e72e02f8
@@ -1,9 +1,6 @@
|
||||
/*
|
||||
* Author: Yevgeniy Kiveisha <yevgeniy.kiveisha@intel.com>
|
||||
* Copyright (c) 2014 Intel Corporation.
|
||||
*
|
||||
* Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
|
||||
* 8/24/2011 by Jeff Rowberg <jeff@rowberg.net>
|
||||
* Author: Jon Trulson <jtrulson@ics.com>
|
||||
* Copyright (c) 2015 Intel Corporation.
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining
|
||||
* a copy of this software and associated documentation files (the
|
||||
@@ -24,188 +21,100 @@
|
||||
* OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION
|
||||
* WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <string>
|
||||
#include <mraa/i2c.h>
|
||||
#include "mpu60x0.h"
|
||||
#include "ak8975.h"
|
||||
|
||||
#define MPU6050_ADDRESS_AD0_LOW 0x68 // address pin low (GND), default for InvenSense evaluation board
|
||||
#define MPU6050_ADDRESS_AD0_HIGH 0x69 // address pin high (VCC)
|
||||
#define ADDR MPU6050_ADDRESS_AD0_LOW // device address
|
||||
#define MPU9150_I2C_BUS 0
|
||||
#define MPU9150_DEFAULT_I2C_ADDR MPU60X0_DEFAULT_I2C_ADDR
|
||||
|
||||
// registers address
|
||||
#define MPU6050_CLOCK_PLL_XGYRO 0x01
|
||||
#define MPU6050_GYRO_FS_250 0x00
|
||||
#define MPU6050_ACCEL_FS_2 0x00
|
||||
#define MPU6050_RA_INT_PIN_CFG 0x37
|
||||
|
||||
#define MPU6050_RA_ACCEL_XOUT_H 0x3B
|
||||
#define MPU6050_RA_ACCEL_XOUT_L 0x3C
|
||||
#define MPU6050_RA_ACCEL_YOUT_H 0x3D
|
||||
#define MPU6050_RA_ACCEL_YOUT_L 0x3E
|
||||
#define MPU6050_RA_ACCEL_ZOUT_H 0x3F
|
||||
#define MPU6050_RA_ACCEL_ZOUT_L 0x40
|
||||
#define MPU6050_RA_TEMP_OUT_H 0x41
|
||||
#define MPU6050_RA_TEMP_OUT_L 0x42
|
||||
#define MPU6050_RA_GYRO_XOUT_H 0x43
|
||||
#define MPU6050_RA_GYRO_XOUT_L 0x44
|
||||
#define MPU6050_RA_GYRO_YOUT_H 0x45
|
||||
#define MPU6050_RA_GYRO_YOUT_L 0x46
|
||||
#define MPU6050_RA_GYRO_ZOUT_H 0x47
|
||||
#define MPU6050_RA_GYRO_ZOUT_L 0x48
|
||||
|
||||
#define MPU6050_RA_CONFIG 0x1A
|
||||
#define MPU6050_CFG_DLPF_CFG_BIT 2
|
||||
#define MPU6050_CFG_DLPF_CFG_LENGTH 3
|
||||
|
||||
#define MPU6050_RA_GYRO_CONFIG 0x1B
|
||||
#define MPU6050_GCONFIG_FS_SEL_BIT 4
|
||||
#define MPU6050_GCONFIG_FS_SEL_LENGTH 2
|
||||
|
||||
#define MPU6050_RA_ACCEL_CONFIG 0x1C
|
||||
#define MPU6050_ACONFIG_AFS_SEL_BIT 4
|
||||
#define MPU6050_ACONFIG_AFS_SEL_LENGTH 2
|
||||
|
||||
// magnotometer
|
||||
#define MPU9150_RA_MAG_ADDRESS 0x0C
|
||||
#define MPU9150_RA_MAG_XOUT_L 0x03
|
||||
|
||||
#define MPU6050_RA_PWR_MGMT_1 0x6B
|
||||
#define MPU6050_PWR1_CLKSEL_BIT 2
|
||||
#define MPU6050_PWR1_CLKSEL_LENGTH 3
|
||||
#define MPU6050_PWR1_SLEEP_BIT 6
|
||||
|
||||
#define MPU6050_RA_INT_PIN_CFG 0x37
|
||||
|
||||
// temperature
|
||||
#define MPU6050_PWR1_TEMP_DIS_BIT 3
|
||||
#define MPU6050_RA_WHO_AM_I 0x75
|
||||
#define MPU6050_WHO_AM_I_BIT 6
|
||||
#define MPU6050_WHO_AM_I_LENGTH 6
|
||||
|
||||
#define SMOOTH_TIMES 10.0
|
||||
|
||||
#define HIGH 1
|
||||
#define LOW 0
|
||||
|
||||
namespace upm {
|
||||
|
||||
struct Vector3DRaw {
|
||||
uint16_t axisX;
|
||||
uint16_t axisY;
|
||||
uint16_t axisZ;
|
||||
};
|
||||
/**
|
||||
* @brief MPU9150 accelerometer library
|
||||
* @defgroup mpu9150 libupm-mpu9150
|
||||
* @ingroup seeed i2c gpio accelerometer compass
|
||||
*/
|
||||
|
||||
struct Vector3D {
|
||||
double axisX;
|
||||
double axisY;
|
||||
double axisZ;
|
||||
};
|
||||
/**
|
||||
* @library mpu9150
|
||||
* @sensor mpu9150
|
||||
* @comname MPU9150 Inertial Measurement Unit
|
||||
* @altname Grove IMU 9DOF
|
||||
* @type accelerometer compass
|
||||
* @man seeed
|
||||
* @web http://www.seeedstudio.com/wiki/Grove_-_IMU_9DOF_v1.0
|
||||
* @con i2c gpio
|
||||
*
|
||||
* @brief API for MPU9150 chip (Accelerometer, Gyro and Magnometer Sensor)
|
||||
*
|
||||
* This file defines the MPU9150 interface for libmpu9150
|
||||
*
|
||||
* @image html mpu9150.jpg
|
||||
* @snippet mpu9150.cxx Interesting
|
||||
*/
|
||||
|
||||
struct AxisData {
|
||||
Vector3DRaw rawData;
|
||||
Vector3D sumData;
|
||||
Vector3D data;
|
||||
};
|
||||
class MPU9150: public MPU60X0
|
||||
{
|
||||
public:
|
||||
/**
|
||||
* MPU9150 constructor
|
||||
*
|
||||
* @param bus i2c bus to use
|
||||
* @param address the address for this device
|
||||
* @param magAddress the address of the connected magnetometer
|
||||
*/
|
||||
MPU9150 (int bus=MPU9150_I2C_BUS, int address=MPU9150_DEFAULT_I2C_ADDR,
|
||||
int magAddress=AK8975_DEFAULT_I2C_ADDR);
|
||||
|
||||
/**
|
||||
* @brief MPU9150 accelerometer library
|
||||
* @defgroup mpu9150 libupm-mpu9150
|
||||
* @ingroup seeed i2c accelerometer compass
|
||||
*/
|
||||
/**
|
||||
* @library mpu9150
|
||||
* @sensor mpu9150
|
||||
* @comname MPU9150 Inertial Measurement Unit
|
||||
* @altname Grove IMU 9DOF
|
||||
* @type accelerometer compass
|
||||
* @man seeed
|
||||
* @web http://www.seeedstudio.com/wiki/Grove_-_IMU_9DOF_v1.0
|
||||
* @con i2c
|
||||
*
|
||||
* @brief API for MPU9150 chip (Accelerometer, Gyro and Magnometer Sensor)
|
||||
*
|
||||
* This file defines the MPU9150 interface for libmpu9150
|
||||
*
|
||||
* @image html mpu9150.jpg
|
||||
* @snippet mpu9150.cxx Interesting
|
||||
*/
|
||||
class MPU9150 {
|
||||
public:
|
||||
/**
|
||||
* Instanciates a MPU9150 object
|
||||
*
|
||||
* @param bus number of used bus
|
||||
* @param devAddr addres of used i2c device
|
||||
*/
|
||||
MPU9150 (int bus=0, int devAddr=0x68);
|
||||
/**
|
||||
* MPU9150 Destructor
|
||||
*/
|
||||
~MPU9150 ();
|
||||
|
||||
/**
|
||||
* MPU9150 object destructor, basicaly it close i2c connection.
|
||||
*/
|
||||
~MPU9150 ();
|
||||
/**
|
||||
* set up initial values and start operation
|
||||
*
|
||||
* @return true if successful
|
||||
*/
|
||||
bool init();
|
||||
|
||||
/**
|
||||
* Initiate MPU9150 chips
|
||||
*/
|
||||
mraa_result_t initSensor ();
|
||||
/**
|
||||
* take a measurement and store the current sensor values
|
||||
* internally. Note, these user facing registers are only updated
|
||||
* from the internal device sensor values when the i2c serial
|
||||
* traffic is 'idle'. So, if you are reading the values too fast,
|
||||
* the bus may never be idle, and you will just end up reading
|
||||
* the same values over and over.
|
||||
*
|
||||
* Unfortunately, it is is not clear how long 'idle' actually
|
||||
* means, so if you see this behavior, reduce the rate at which
|
||||
* you are calling update().
|
||||
*/
|
||||
void update();
|
||||
|
||||
/**
|
||||
* Get identity of the device
|
||||
*/
|
||||
uint8_t getDeviceID ();
|
||||
/**
|
||||
* return the compensated values for the x, y, and z axes. The
|
||||
* unit of measurement is in micro-teslas (uT).
|
||||
*
|
||||
* @param x pointer to returned X axis value
|
||||
* @param y pointer to returned Y axis value
|
||||
* @param z pointer to returned Z axis value
|
||||
*/
|
||||
void getMagnetometer(float *x, float *y, float *z);
|
||||
|
||||
/**
|
||||
* Get the Accelerometer, Gyro and Compass data from the chip and
|
||||
* save it in private section.
|
||||
*/
|
||||
void getData ();
|
||||
|
||||
/**
|
||||
* @param data structure with 3 axis (x,y,z)
|
||||
*/
|
||||
mraa_result_t getAcceleromter (Vector3D * data);
|
||||
protected:
|
||||
// magnetometer instance
|
||||
AK8975* m_mag;
|
||||
|
||||
/**
|
||||
* @param data structure with 3 axis (x,y,z)
|
||||
*/
|
||||
mraa_result_t getGyro (Vector3D * data);
|
||||
|
||||
/**
|
||||
* @param data structure with 3 axis (x,y,z)
|
||||
*/
|
||||
mraa_result_t getMagnometer (Vector3D * data);
|
||||
|
||||
/**
|
||||
* Read on die temperature from the chip
|
||||
*/
|
||||
float getTemperature ();
|
||||
|
||||
/**
|
||||
* Return name of the component
|
||||
*/
|
||||
std::string name()
|
||||
{
|
||||
return m_name;
|
||||
}
|
||||
|
||||
private:
|
||||
std::string m_name;
|
||||
|
||||
int m_i2cAddr;
|
||||
int m_bus;
|
||||
mraa_i2c_context m_i2Ctx;
|
||||
|
||||
AxisData axisMagnetomer;
|
||||
AxisData axisAcceleromter;
|
||||
AxisData axisGyroscope;
|
||||
|
||||
uint16_t i2cReadReg_N (int reg, unsigned int len, uint8_t * buffer);
|
||||
mraa_result_t i2cWriteReg (uint8_t reg, uint8_t value);
|
||||
int updateRegBits (uint8_t reg, uint8_t bitStart,
|
||||
uint8_t length, uint16_t data);
|
||||
uint8_t getRegBits (uint8_t reg, uint8_t bitStart,
|
||||
uint8_t length, uint8_t * data);
|
||||
};
|
||||
private:
|
||||
int m_i2cBus;
|
||||
uint8_t m_magAddress;
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user