MAV'RIC
Classes | Public Types | Public Member Functions | Static Public Member Functions | Static Public Attributes
Mpu_9250 Class Reference

Driver for sensor MPU 9250. More...

#include <mpu_9250.hpp>

Inheritance diagram for Mpu_9250:
Inheritance graph
[legend]
Collaboration diagram for Mpu_9250:
Collaboration graph
[legend]

List of all members.

Classes

struct  conf_t
 Configuration structure for mpu 9250. More...

Public Types

enum  acc_filter_t {
  ACC_LOWPASS_460_HZ = 0x00, ACC_LOWPASS_184_HZ = 0x01, ACC_LOWPASS_92_HZ = 0x02, ACC_LOWPASS_41_HZ = 0x03,
  ACC_LOWPASS_20_HZ = 0x04, ACC_LOWPASS_10_HZ = 0x05, ACC_LOWPASS_5_HZ = 0x06
}
enum  acc_range_t { ACC_2G = 0x00, ACC_4G = 0x08, ACC_8G = 0x10, ACC_16G = 0x18 }
enum  gyro_filter_t {
  GYRO_LOWPASS_250_HZ = 0x00, GYRO_LOWPASS_184_HZ = 0x01, GYRO_LOWPASS_92_HZ = 0x02, GYRO_LOWPASS_41_HZ = 0x03,
  GYRO_LOWPASS_20_HZ = 0x04, GYRO_LOWPASS_10_HZ = 0x05, GYRO_LOWPASS_5_HZ = 0x06
}
enum  gyro_range_t { GYRO_250_DEG = 0x00, GYRO_500_DEG = 0x08, GYRO_1000_DEG = 0x10, GYRO_2000_DEG = 0x18 }

Public Member Functions

 Mpu_9250 (Spi &spi, Gpio &nss_gpio, const conf_t config=mpu_9250_default_config())
 Constructor.
bool init (void)
 Initialise the sensor.
bool update_acc (void)
 Main update function.
bool update_gyr (void)
bool update_mag (void)
const float & last_update_us (void) const
 Get last update time in microseconds.
const std::array< float, 3 > & gyro (void) const
 Get X, Y and Z components of angular velocity.
const float & gyro_X (void) const
 Get X component of angular velocity.
const float & gyro_Y (void) const
 Get Y component of angular velocity.
const float & gyro_Z (void) const
 Get Z component of angular velocity.
const std::array< float, 3 > & acc (void) const
 Get X, Y and Z components of acceleration.
const float & acc_X (void) const
 Get X component of acceleration.
const float & acc_Y (void) const
 Get Y component of acceleration.
const float & acc_Z (void) const
 Get Z component of acceleration.
const std::array< float, 3 > & mag (void) const
 Get X, Y and Z components of magnetic field.
const float & mag_X (void) const
 Get X component of magnetic field.
const float & mag_Y (void) const
 Get Y component of magnetic field.
const float & mag_Z (void) const
 Get Z component of magnetic field.
const float & temperature (void) const
 Get sensor temperature.
bool mpu_reset (void)
 Reset acc and gyro.
bool mag_reset (void)
 Reset magnetometer.
bool mag_read_reg (uint8_t reg, uint8_t *in_data)
 Read register from magnetometer.
bool mag_write_reg (uint8_t reg, uint8_t *out_data)
 Write values in register of ak8963.
bool write_reg (uint8_t reg, uint8_t *out_data, uint32_t nbytes=1)
 Write register of mpu 9250.
bool read_reg (uint8_t reg, uint8_t *in_data, uint32_t nbytes=1)
 Read register of mpu 9250.

Static Public Member Functions

static conf_t mpu_9250_default_config ()
 Default configuration for mpu 9250.

Static Public Attributes

static const uint8_t AK8963_WHOAMI_REG = 0x00
static const uint8_t AK8963_ST1_REG = 0x02
static const uint8_t AK8963_HXL = 0x03
static const uint8_t AK8963_ST2_REG = 0x09
static const uint8_t AK8963_CNTL1_CONT_8HZ = 0x02
static const uint8_t AK8963_CNTL1_CONT_100HZ = 0x06
static const uint8_t AK8963_CNTL1_16BITS = 0x10
static const uint8_t AK8963_CNTL1_REG = 0x0A
static const uint8_t AK8963_CNTL2_REG = 0x0B
static const uint8_t AK8963_CNTL2_SRST = 0x01
static const uint8_t AK8963_WHOAMI_ID = 0x48
static const uint8_t AK8963_ADDR = 0x0C
static const uint8_t SMPLRT_DIV_REG = 0x19
static const uint8_t DLPF_CFG_REG = 0x1A
static const uint8_t GYRO_CFG_REG = 0x1B
static const uint8_t ACCEL_CFG_REG = 0x1C
static const uint8_t ACCEL_CFG2_REG = 0x1D
static const uint8_t SLV0_ADDR_REG = 0x25
static const uint8_t SLV0_REG_REG = 0x26
static const uint8_t SLV0_CTRL_REG = 0x27
static const uint8_t SLV4_ADDR_REG = 0x31
static const uint8_t SLV4_REG_REG = 0x32
static const uint8_t SLV4_DO_REG = 0x33
static const uint8_t SLV4_CTRL_REG = 0x34
static const uint8_t SLV4_DI_REG = 0x35
static const uint8_t I2C_MST_STATUS_REG = 0x36
static const uint8_t ACCEL_X_OUT_MSB = 0x3B
static const uint8_t ACCEL_X_OUT_LSB = 0x3C
static const uint8_t ACCEL_Y_OUT_MSB = 0x3D
static const uint8_t ACCEL_Y_OUT_LSB = 0x3E
static const uint8_t ACCEL_Z_OUT_MSB = 0x3F
static const uint8_t ACCEL_Z_OUT_LSB = 0x40
static const uint8_t GYRO_X_OUT_MSB = 0x43
static const uint8_t GYRO_X_OUT_LSB = 0x44
static const uint8_t GYRO_Y_OUT_MSB = 0x45
static const uint8_t GYRO_Y_OUT_LSB = 0x46
static const uint8_t GYRO_Z_OUT_MSB = 0x47
static const uint8_t GYRO_Z_OUT_LSB = 0x48
static const uint8_t EXT_SENS_DATA_00 = 0x49
static const uint8_t USER_CTRL_REG = 0x6A
static const uint8_t PWR_MGMT_REG = 0x6B
static const uint8_t WHOAMI_REG = 0x75
static const uint8_t READ_FLAG = 0x80
static const uint8_t WRITE_FLAG = 0x7f
static const uint8_t WHOAMI_ID = 0x71
static const uint8_t I2C_MST_SLV4_NACK = 0x10
static const uint8_t I2C_MST_SLV4_DONE = 0x40
static const uint8_t I2CSLV_EN = 0x80
static const uint8_t PWRMGMT_IMU_RST = 0x80
static const uint8_t PWRMGMT_PLL_X_CLK = 0x01
static const uint8_t USERCTL_DIS_I2C = 0x10
static const uint8_t USERCTL_I2C_MST_EN = 0x20
static const uint8_t USERCTL_GYRO_RST = 0x01

Detailed Description

Driver for sensor MPU 9250.

This sensor is at the same time a accelerometer and a gyroscope and a magnetometer The inherited method Accelerometer::update is implemented as Mpu9250::update_acc The inherited method Gyroscope::update is implemented as Mpu9250::update_gyr The inherited method Magnetometer::update is implemented as Mpu9250::update_mag


Constructor & Destructor Documentation

Mpu_9250::Mpu_9250 ( Spi spi,
Gpio nss_gpio,
const conf_t  config = mpu_9250_default_config() 
)

Constructor.

Parameters:
spiReference to SPI device
nss_gpioReference to Slave Select GPIO
configDevice configuration

Member Function Documentation

const std::array< float, 3 > & Mpu_9250::acc ( void  ) const [virtual]

Get X, Y and Z components of acceleration.

This is raw data, so X, Y and Z components are biased, are scaled, and given in the sensor frame (not in the UAV frame). Use an Imu object to handle bias removal and axis rotations

Returns:
Value

Implements Accelerometer.

const float & Mpu_9250::acc_X ( void  ) const [virtual]

Get X component of acceleration.

This is raw data, so X, Y and Z components are biased, are scaled, and given in the sensor frame (not in the UAV frame). Use an Imu object to handle bias removal and axis rotations

Returns:
Value

Implements Accelerometer.

const float & Mpu_9250::acc_Y ( void  ) const [virtual]

Get Y component of acceleration.

This is raw data, so X, Y and Z components are biased, are scaled, and given in the sensor frame (not in the UAV frame). Use an Imu object to handle bias removal and axis rotations

Returns:
Value

Implements Accelerometer.

const float & Mpu_9250::acc_Z ( void  ) const [virtual]

Get Z component of acceleration.

This is raw data, so X, Y and Z components are biased, are scaled, and given in the sensor frame (not in the UAV frame). Use an Imu object to handle bias removal and axis rotations

Returns:
Value

Implements Accelerometer.

const std::array< float, 3 > & Mpu_9250::gyro ( void  ) const [virtual]

Get X, Y and Z components of angular velocity.

This is raw data, so X, Y and Z components are biased, are scaled, and given in the sensor frame (not in the UAV frame). Use an Imu object to handle bias removal and axis rotations

Returns:
Value

Implements Gyroscope.

const float & Mpu_9250::gyro_X ( void  ) const [virtual]

Get X component of angular velocity.

This is raw data, so X, Y and Z components are biased, are scaled, and given in the sensor frame (not in the UAV frame). Use an Imu object to handle bias removal and axis rotations

Returns:
Value

Implements Gyroscope.

const float & Mpu_9250::gyro_Y ( void  ) const [virtual]

Get Y component of angular velocity.

This is raw data, so X, Y and Z components are biased, are scaled, and given in the sensor frame (not in the UAV frame). Use an Imu object to handle bias removal and axis rotations

Returns:
Value

Implements Gyroscope.

const float & Mpu_9250::gyro_Z ( void  ) const [virtual]

Get Z component of angular velocity.

This is raw data, so X, Y and Z components are biased, are scaled, and given in the sensor frame (not in the UAV frame). Use an Imu object to handle bias removal and axis rotations

Returns:
Value

Implements Gyroscope.

bool Mpu_9250::init ( void  ) [virtual]

Initialise the sensor.

Sends configuration via SPI, the SPI peripheral must be activated before this method is called

Returns:
true Success
false Failed

Implements Accelerometer.

Here is the call graph for this function:

Here is the caller graph for this function:

const float & Mpu_9250::last_update_us ( void  ) const [virtual]

Get last update time in microseconds.

Returns:
Update time

Implements Accelerometer.

const std::array< float, 3 > & Mpu_9250::mag ( void  ) const [virtual]

Get X, Y and Z components of magnetic field.

This is raw data, so X, Y and Z components are biased, not scaled, and given in the sensor frame (not in the UAV frame). Use an Imu object to handle bias removal, scaling and axis rotations

Returns:
Value

Implements Magnetometer.

bool Mpu_9250::mag_read_reg ( uint8_t  reg,
uint8_t *  in_data 
)

Read register from magnetometer.

Parameters:
regRegister to read from
in_dataIncoming data
Returns:
success

Here is the call graph for this function:

Here is the caller graph for this function:

bool Mpu_9250::mag_reset ( void  )

Reset magnetometer.

Returns:
success

Here is the call graph for this function:

Here is the caller graph for this function:

bool Mpu_9250::mag_write_reg ( uint8_t  reg,
uint8_t *  out_data 
)

Write values in register of ak8963.

Parameters:
regRegister to write to
out_dataOutgoing data
Returns:
success

Here is the call graph for this function:

Here is the caller graph for this function:

const float & Mpu_9250::mag_X ( void  ) const [virtual]

Get X component of magnetic field.

This is raw data, so X, Y and Z components are biased, not scaled, and given in the sensor frame (not in the UAV frame). Use an Imu object to handle bias removal, scaling and axis rotations

Returns:
Value

Implements Magnetometer.

const float & Mpu_9250::mag_Y ( void  ) const [virtual]

Get Y component of magnetic field.

This is raw data, so X, Y and Z components are biased, not scaled, and given in the sensor frame (not in the UAV frame). Use an Imu object to handle bias removal, scaling and axis rotations

Returns:
Value

Implements Magnetometer.

const float & Mpu_9250::mag_Z ( void  ) const [virtual]

Get Z component of magnetic field.

This is raw data, so X, Y and Z components are biased, not scaled, and given in the sensor frame (not in the UAV frame). Use an Imu object to handle bias removal, scaling and axis rotations

Returns:
Value

Implements Magnetometer.

static conf_t Mpu_9250::mpu_9250_default_config ( ) [inline, static]

Default configuration for mpu 9250.

Returns:
Conf structure
bool Mpu_9250::mpu_reset ( void  )

Reset acc and gyro.

Returns:
success

Here is the call graph for this function:

Here is the caller graph for this function:

bool Mpu_9250::read_reg ( uint8_t  reg,
uint8_t *  in_data,
uint32_t  nbytes = 1 
)

Read register of mpu 9250.

Read data at the specified register, burst read possible by specifying the number of bytes to read

Parameters:
regRegister to read from
in_dataIncoming data
nbytesNumber of bytes to read
Returns:
success

Here is the call graph for this function:

Here is the caller graph for this function:

const float & Mpu_9250::temperature ( void  ) const [virtual]

Get sensor temperature.

Returns:
Value

Implements Accelerometer.

bool Mpu_9250::update_acc ( void  ) [virtual]

Main update function.

Get new data from the sensor

Returns:
true Success
false Failed

Implements Mpu_9250_acc.

Here is the call graph for this function:

bool Mpu_9250::write_reg ( uint8_t  reg,
uint8_t *  out_data,
uint32_t  nbytes = 1 
)

Write register of mpu 9250.

Write data to the specified register, burst write possible by specifying the number of bytes to write

Parameters:
regRegister to write to
out_dataOutgoing data
nbytesNumber of bytes to write
Returns:
success

Here is the call graph for this function:

Here is the caller graph for this function:


The documentation for this class was generated from the following files:
 All Classes Files Functions Variables Typedefs Enumerations Enumerator Friends Defines