PX4 Firmware
PX4 Autopilot Software http://px4.io
MPU6000 Class Reference

#include <MPU6000.hpp>

Inheritance diagram for MPU6000:
Collaboration diagram for MPU6000:

Public Member Functions

 MPU6000 (device::Device *interface, enum Rotation rotation, int device_type)
 
virtual ~MPU6000 ()
 
virtual int init ()
 
void print_info ()
 Diagnostics - print some basic information about the driver. More...
 
void print_registers ()
 
int factory_self_test ()
 Test behaviour against factory offsets. More...
 
void test_error ()
 
void start ()
 Start automatic measurement. More...
 
int reset ()
 Reset chip. More...
 

Protected Member Functions

virtual int probe ()
 

Protected Attributes

device::Device_interface
 

Private Member Functions

void Run () override
 
void stop ()
 Stop automatic measurement. More...
 
bool is_icm_device ()
 is_icm_device More...
 
bool is_mpu_device ()
 is_mpu_device More...
 
int measure ()
 Fetch measurements from the sensor and update the report buffers. More...
 
uint8_t read_reg (unsigned reg, uint32_t speed=MPU6000_LOW_BUS_SPEED)
 Read a register from the MPU6000. More...
 
uint16_t read_reg16 (unsigned reg)
 
int write_reg (unsigned reg, uint8_t value)
 Write a register in the MPU6000. More...
 
void modify_reg (unsigned reg, uint8_t clearbits, uint8_t setbits)
 Modify a register in the MPU6000. More...
 
void write_checked_reg (unsigned reg, uint8_t value)
 Write a register in the MPU6000, updating _checked_values. More...
 
int set_accel_range (unsigned max_g)
 Set the MPU6000 measurement range. More...
 
void _set_dlpf_filter (uint16_t frequency_hz)
 
void _set_icm_acc_dlpf_filter (uint16_t frequency_hz)
 
void _set_sample_rate (unsigned desired_sample_rate_hz)
 
void check_registers (void)
 
 MPU6000 (const MPU6000 &)
 
MPU6000 operator= (const MPU6000 &)
 

Private Attributes

int _device_type
 
uint8_t _product {0}
 
unsigned _call_interval {1000}
 product code More...
 
PX4Accelerometer _px4_accel
 
PX4Gyroscope _px4_gyro
 
unsigned _sample_rate {1000}
 
perf_counter_t _sample_perf
 
perf_counter_t _bad_transfers
 
perf_counter_t _bad_registers
 
perf_counter_t _reset_retries
 
perf_counter_t _duplicates
 
uint8_t _register_wait {0}
 
uint64_t _reset_wait {0}
 
uint8_t _checked_values [MPU6000_NUM_CHECKED_REGISTERS]
 
uint8_t _checked_next {0}
 
volatile bool _in_factory_test {false}
 
uint16_t _last_accel [3] {}
 
bool _got_duplicate {false}
 

Static Private Attributes

static constexpr int MPU6000_CHECKED_PRODUCT_ID_INDEX = 0
 
static constexpr int MPU6000_NUM_CHECKED_REGISTERS = 10
 
static constexpr uint8_t _checked_registers [MPU6000_NUM_CHECKED_REGISTERS]
 

Detailed Description

Definition at line 285 of file MPU6000.hpp.

Constructor & Destructor Documentation

◆ MPU6000() [1/2]

MPU6000::MPU6000 ( device::Device interface,
enum Rotation  rotation,
int  device_type 
)

◆ ~MPU6000()

MPU6000::~MPU6000 ( )
virtual

Definition at line 78 of file MPU6000.cpp.

References _bad_registers, _bad_transfers, _duplicates, _reset_retries, _sample_perf, perf_free(), and stop().

Here is the call graph for this function:

◆ MPU6000() [2/2]

MPU6000::MPU6000 ( const MPU6000 )
private

Member Function Documentation

◆ _set_dlpf_filter()

void MPU6000::_set_dlpf_filter ( uint16_t  frequency_hz)
private

Definition at line 305 of file MPU6000.cpp.

References MPU_GYRO_DLPF_CFG_10HZ, MPU_GYRO_DLPF_CFG_188HZ, MPU_GYRO_DLPF_CFG_20HZ, MPU_GYRO_DLPF_CFG_2100HZ_NOLPF, MPU_GYRO_DLPF_CFG_256HZ_NOLPF2, MPU_GYRO_DLPF_CFG_42HZ, MPU_GYRO_DLPF_CFG_5HZ, MPU_GYRO_DLPF_CFG_98HZ, MPUREG_CONFIG, and write_checked_reg().

Referenced by reset().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _set_icm_acc_dlpf_filter()

void MPU6000::_set_icm_acc_dlpf_filter ( uint16_t  frequency_hz)
private

Definition at line 341 of file MPU6000.cpp.

References ICM_ACC_DLPF_CFG_1046HZ_NOLPF, ICM_ACC_DLPF_CFG_10HZ, ICM_ACC_DLPF_CFG_218HZ, ICM_ACC_DLPF_CFG_21HZ, ICM_ACC_DLPF_CFG_420HZ, ICM_ACC_DLPF_CFG_44HZ, ICM_ACC_DLPF_CFG_5HZ, ICM_ACC_DLPF_CFG_99HZ, ICMREG_ACCEL_CONFIG2, and write_checked_reg().

Referenced by reset().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _set_sample_rate()

void MPU6000::_set_sample_rate ( unsigned  desired_sample_rate_hz)
private

Definition at line 281 of file MPU6000.cpp.

References _sample_rate, MPU6000_GYRO_DEFAULT_RATE, MPUREG_SMPLRT_DIV, and write_checked_reg().

Referenced by reset().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ check_registers()

void MPU6000::check_registers ( void  )
private

Definition at line 660 of file MPU6000.cpp.

References _bad_registers, _checked_next, _checked_registers, _checked_values, _register_wait, _reset_wait, BIT_H_RESET, hrt_absolute_time(), is_icm_device(), MPU6000_CHECKED_PRODUCT_ID_INDEX, MPU6000_HIGH_BUS_SPEED, MPU6000_NUM_CHECKED_REGISTERS, MPUREG_ICM_UNDOC1, MPUREG_PWR_MGMT_1, perf_count(), read_reg(), and write_reg().

Referenced by measure().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ factory_self_test()

int MPU6000::factory_self_test ( )

Test behaviour against factory offsets.

Returns
0 on success, 1 on failure

Definition at line 383 of file MPU6000.cpp.

References _in_factory_test, _interface, BITS_FS_250DPS, BITS_GYRO_ST_X, BITS_GYRO_ST_Y, BITS_GYRO_ST_Z, err, f(), int16_t_from_bytes(), MPU6000_HIGH_BUS_SPEED, MPU6000_SET_SPEED, MPUREG_ACCEL_CONFIG, MPUREG_GYRO_CONFIG, MPUREG_INT_STATUS, MPUREG_TRIM1, MPUREG_TRIM2, MPUREG_TRIM3, MPUREG_TRIM4, OK, device::Device::read(), read_reg(), and write_reg().

Referenced by mpu6000::factorytest().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init()

int MPU6000::init ( )
virtual

Definition at line 92 of file MPU6000.cpp.

References OK, probe(), and reset().

Here is the call graph for this function:

◆ is_icm_device()

bool MPU6000::is_icm_device ( )
inlineprivate

is_icm_device

Definition at line 391 of file MPU6000.hpp.

Referenced by check_registers(), measure(), probe(), and reset().

Here is the caller graph for this function:

◆ is_mpu_device()

bool MPU6000::is_mpu_device ( )
inlineprivate

is_mpu_device

Definition at line 395 of file MPU6000.hpp.

References MPU6000_LOW_BUS_SPEED, and MPU_DEVICE_TYPE_MPU6000.

Referenced by probe(), and set_accel_range().

Here is the caller graph for this function:

◆ measure()

int MPU6000::measure ( )
private

Fetch measurements from the sensor and update the report buffers.

Definition at line 721 of file MPU6000.cpp.

References _bad_registers, _bad_transfers, _duplicates, _got_duplicate, _in_factory_test, _interface, _last_accel, _px4_accel, _px4_gyro, _register_wait, _reset_wait, _sample_perf, check_registers(), hrt_absolute_time(), hrt_abstime, int16_t_from_bytes(), is_icm_device(), MPU6000_HIGH_BUS_SPEED, MPU6000_SET_SPEED, MPUREG_INT_STATUS, OK, perf_begin(), perf_count(), perf_end(), perf_event_count(), device::Device::read(), PX4Accelerometer::set_error_count(), PX4Gyroscope::set_error_count(), PX4Accelerometer::set_temperature(), PX4Gyroscope::set_temperature(), PX4Accelerometer::update(), and PX4Gyroscope::update().

Referenced by Run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ modify_reg()

void MPU6000::modify_reg ( unsigned  reg,
uint8_t  clearbits,
uint8_t  setbits 
)
private

Modify a register in the MPU6000.

Bits are cleared before bits are set.

Parameters
regThe register to modify.
clearbitsBits in the register to clear.
setbitsBits in the register to set.

Definition at line 564 of file MPU6000.cpp.

References read_reg(), and write_reg().

Here is the call graph for this function:

◆ operator=()

MPU6000 MPU6000::operator= ( const MPU6000 )
private

◆ print_info()

void MPU6000::print_info ( )

Diagnostics - print some basic information about the driver.

Definition at line 886 of file MPU6000.cpp.

References _bad_registers, _bad_transfers, _duplicates, _px4_accel, _px4_gyro, _reset_retries, _sample_perf, perf_print_counter(), PX4Accelerometer::print_status(), and PX4Gyroscope::print_status().

Referenced by mpu6000::info().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ print_registers()

void MPU6000::print_registers ( )

Definition at line 899 of file MPU6000.cpp.

References MPUREG_PRODUCT_ID, and read_reg().

Referenced by mpu6000::regdump(), and test_error().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ probe()

int MPU6000::probe ( )
protectedvirtual

Definition at line 203 of file MPU6000.cpp.

References _checked_values, _device_type, _product, ICM20602_REV_01, ICM20602_REV_02, ICM20608_REV_FF, ICM20689_REV_03, ICM20689_REV_04, ICM20689_REV_FE, ICM_WHOAMI_20602, ICM_WHOAMI_20608, ICM_WHOAMI_20689, is_icm_device(), is_mpu_device(), MPU6000_CHECKED_PRODUCT_ID_INDEX, MPU6000_REV_C4, MPU6000_REV_C5, MPU6000_REV_D10, MPU6000_REV_D6, MPU6000_REV_D7, MPU6000_REV_D8, MPU6000_REV_D9, MPU6000ES_REV_C4, MPU6000ES_REV_C5, MPU6000ES_REV_D6, MPU6000ES_REV_D7, MPU6000ES_REV_D8, MPU6050_REV_D8, MPU_DEVICE_TYPE_ICM20602, MPU_DEVICE_TYPE_ICM20608, MPU_DEVICE_TYPE_ICM20689, MPU_DEVICE_TYPE_MPU6000, MPU_WHOAMI_6000, MPUREG_PRODUCT_ID, MPUREG_WHOAMI, OK, and read_reg().

Referenced by init().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ read_reg()

uint8_t MPU6000::read_reg ( unsigned  reg,
uint32_t  speed = MPU6000_LOW_BUS_SPEED 
)
private

Read a register from the MPU6000.

Parameters
Theregister to read.
Returns
The value that was read.

Definition at line 539 of file MPU6000.cpp.

References _interface, MPU6000_SET_SPEED, and device::Device::read().

Referenced by check_registers(), factory_self_test(), modify_reg(), print_registers(), probe(), and reset().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ read_reg16()

uint16_t MPU6000::read_reg16 ( unsigned  reg)
private

Definition at line 547 of file MPU6000.cpp.

References _interface, arraySize, MPU6000_LOW_SPEED_OP, and device::Device::read().

Here is the call graph for this function:

◆ reset()

int MPU6000::reset ( )

Reset chip.

Resets the chip and measurements ranges, but not scale and offset.

Definition at line 110 of file MPU6000.cpp.

References _interface, _px4_gyro, _reset_retries, _reset_wait, _set_dlpf_filter(), _set_icm_acc_dlpf_filter(), _set_sample_rate(), BIT_H_RESET, BIT_I2C_IF_DIS, BIT_INT_ANYRD_2CLEAR, BIT_RAW_RDY_EN, BITS_FS_2000DPS, device::Device::DeviceBusType_I2C, f(), device::Device::get_device_bus_type(), hrt_absolute_time(), is_icm_device(), MPU6000_ACCEL_DEFAULT_RANGE_G, MPU6000_DEFAULT_ONCHIP_FILTER_FREQ, MPU_CLK_SEL_PLLGYROZ, MPUREG_GYRO_CONFIG, MPUREG_ICM_UNDOC1, MPUREG_ICM_UNDOC1_VALUE, MPUREG_INT_ENABLE, MPUREG_INT_PIN_CFG, MPUREG_PWR_MGMT_1, MPUREG_USER_CTRL, OK, perf_count(), read_reg(), set_accel_range(), PX4Gyroscope::set_scale(), state, write_checked_reg(), and write_reg().

Referenced by init(), and mpu6000::reset().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ Run()

void MPU6000::Run ( )
overrideprivate

Definition at line 653 of file MPU6000.cpp.

References measure().

Here is the call graph for this function:

◆ set_accel_range()

int MPU6000::set_accel_range ( unsigned  max_g)
private

Set the MPU6000 measurement range.

Parameters
max_gThe maximum G value the range must support.
Returns
OK if the value can be supported, -ERANGE otherwise.

Definition at line 585 of file MPU6000.cpp.

References _product, _px4_accel, CONSTANTS_ONE_G, f(), is_mpu_device(), MPU6000_REV_C4, MPU6000_REV_C5, MPU6000ES_REV_C4, MPU6000ES_REV_C5, MPUREG_ACCEL_CONFIG, OK, PX4Accelerometer::set_scale(), and write_checked_reg().

Referenced by reset().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ start()

void MPU6000::start ( )

Start automatic measurement.

Definition at line 633 of file MPU6000.cpp.

References _call_interval, MPU6000_TIMER_REDUCTION, and stop().

Here is the call graph for this function:

◆ stop()

void MPU6000::stop ( )
private

Stop automatic measurement.

Definition at line 644 of file MPU6000.cpp.

References _last_accel.

Referenced by start(), and ~MPU6000().

Here is the caller graph for this function:

◆ test_error()

void MPU6000::test_error ( )

Definition at line 526 of file MPU6000.cpp.

References _in_factory_test, _interface, data, MPU6000_LOW_BUS_SPEED, MPU6000_SET_SPEED, MPUREG_INT_STATUS, print_registers(), and device::Device::read().

Referenced by mpu6000::testerror().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_checked_reg()

void MPU6000::write_checked_reg ( unsigned  reg,
uint8_t  value 
)
private

Write a register in the MPU6000, updating _checked_values.

Parameters
regThe register to write.
valueThe new value to write.

Definition at line 573 of file MPU6000.cpp.

References _checked_registers, _checked_values, MPU6000_NUM_CHECKED_REGISTERS, and write_reg().

Referenced by _set_dlpf_filter(), _set_icm_acc_dlpf_filter(), _set_sample_rate(), reset(), and set_accel_range().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_reg()

int MPU6000::write_reg ( unsigned  reg,
uint8_t  value 
)
private

Write a register in the MPU6000.

Parameters
regThe register to write.
valueThe new value to write.

Definition at line 557 of file MPU6000.cpp.

References _interface, MPU6000_LOW_SPEED_OP, and device::Device::write().

Referenced by check_registers(), factory_self_test(), modify_reg(), reset(), and write_checked_reg().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ _bad_registers

perf_counter_t MPU6000::_bad_registers
private

Definition at line 346 of file MPU6000.hpp.

Referenced by check_registers(), measure(), print_info(), and ~MPU6000().

◆ _bad_transfers

perf_counter_t MPU6000::_bad_transfers
private

Definition at line 345 of file MPU6000.hpp.

Referenced by measure(), print_info(), and ~MPU6000().

◆ _call_interval

unsigned MPU6000::_call_interval {1000}
private

product code

Definition at line 337 of file MPU6000.hpp.

Referenced by start().

◆ _checked_next

uint8_t MPU6000::_checked_next {0}
private

Definition at line 373 of file MPU6000.hpp.

Referenced by check_registers().

◆ _checked_registers

constexpr uint8_t MPU6000::_checked_registers
staticprivate

◆ _checked_values

uint8_t MPU6000::_checked_values[MPU6000_NUM_CHECKED_REGISTERS]
private

Definition at line 372 of file MPU6000.hpp.

Referenced by check_registers(), probe(), and write_checked_reg().

◆ _device_type

int MPU6000::_device_type
private

Definition at line 334 of file MPU6000.hpp.

Referenced by MPU6000(), and probe().

◆ _duplicates

perf_counter_t MPU6000::_duplicates
private

Definition at line 348 of file MPU6000.hpp.

Referenced by measure(), print_info(), and ~MPU6000().

◆ _got_duplicate

bool MPU6000::_got_duplicate {false}
private

Definition at line 381 of file MPU6000.hpp.

Referenced by measure().

◆ _in_factory_test

volatile bool MPU6000::_in_factory_test {false}
private

Definition at line 377 of file MPU6000.hpp.

Referenced by factory_self_test(), measure(), and test_error().

◆ _interface

device::Device* MPU6000::_interface
protected

Definition at line 326 of file MPU6000.hpp.

Referenced by factory_self_test(), measure(), read_reg(), read_reg16(), reset(), test_error(), and write_reg().

◆ _last_accel

uint16_t MPU6000::_last_accel[3] {}
private

Definition at line 380 of file MPU6000.hpp.

Referenced by measure(), and stop().

◆ _product

uint8_t MPU6000::_product {0}
private

Definition at line 335 of file MPU6000.hpp.

Referenced by probe(), and set_accel_range().

◆ _px4_accel

PX4Accelerometer MPU6000::_px4_accel
private

Definition at line 339 of file MPU6000.hpp.

Referenced by measure(), MPU6000(), print_info(), and set_accel_range().

◆ _px4_gyro

PX4Gyroscope MPU6000::_px4_gyro
private

Definition at line 340 of file MPU6000.hpp.

Referenced by measure(), MPU6000(), print_info(), and reset().

◆ _register_wait

uint8_t MPU6000::_register_wait {0}
private

Definition at line 350 of file MPU6000.hpp.

Referenced by check_registers(), and measure().

◆ _reset_retries

perf_counter_t MPU6000::_reset_retries
private

Definition at line 347 of file MPU6000.hpp.

Referenced by print_info(), reset(), and ~MPU6000().

◆ _reset_wait

uint64_t MPU6000::_reset_wait {0}
private

Definition at line 351 of file MPU6000.hpp.

Referenced by check_registers(), measure(), and reset().

◆ _sample_perf

perf_counter_t MPU6000::_sample_perf
private

Definition at line 344 of file MPU6000.hpp.

Referenced by measure(), print_info(), and ~MPU6000().

◆ _sample_rate

unsigned MPU6000::_sample_rate {1000}
private

Definition at line 342 of file MPU6000.hpp.

Referenced by _set_sample_rate().

◆ MPU6000_CHECKED_PRODUCT_ID_INDEX

constexpr int MPU6000::MPU6000_CHECKED_PRODUCT_ID_INDEX = 0
staticprivate

Definition at line 356 of file MPU6000.hpp.

Referenced by check_registers(), and probe().

◆ MPU6000_NUM_CHECKED_REGISTERS

constexpr int MPU6000::MPU6000_NUM_CHECKED_REGISTERS = 10
staticprivate

Definition at line 357 of file MPU6000.hpp.

Referenced by check_registers(), and write_checked_reg().


The documentation for this class was generated from the following files: