PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <mpu9250.h>
Public Member Functions | |
MPU9250 (device::Device *interface, device::Device *mag_interface, enum Rotation rotation) | |
virtual | ~MPU9250 () |
virtual int | init () |
uint8_t | get_whoami () |
void | print_info () |
Diagnostics - print some basic information about the driver. More... | |
Protected Member Functions | |
virtual int | probe () |
whoami result More... | |
void | Run () override |
Protected Attributes | |
device::Device * | _interface |
uint8_t | _whoami {0} |
Private Member Functions | |
bool | check_null_data (uint16_t *data, uint8_t size) |
bool | check_duplicate (uint8_t *accel_data) |
void | start () |
void | stop () |
int | reset () |
int | reset_mpu () |
Resets the main chip (excluding the magnetometer if any). More... | |
void | measure () |
Fetch measurements from the sensor and update the report buffers. More... | |
uint8_t | read_reg (unsigned reg, uint32_t speed=MPU9250_LOW_BUS_SPEED) |
Read a register from the mpu. More... | |
uint16_t | read_reg16 (unsigned reg) |
uint8_t | read_reg_range (unsigned start_reg, uint32_t speed, uint8_t *buf, uint16_t count) |
Read a register range from the mpu. More... | |
void | write_reg (unsigned reg, uint8_t value) |
Write a register in the mpu. More... | |
void | modify_reg (unsigned reg, uint8_t clearbits, uint8_t setbits) |
Modify a register in the mpu. More... | |
void | write_checked_reg (unsigned reg, uint8_t value) |
Write a register in the mpu, updating _checked_values. More... | |
void | modify_checked_reg (unsigned reg, uint8_t clearbits, uint8_t setbits) |
Modify a checked register in the mpu. More... | |
int | set_accel_range (unsigned max_g) |
Set the mpu measurement range. More... | |
uint16_t | swap16 (uint16_t val) |
Swap a 16-bit value read from the mpu to native byte order. More... | |
bool | is_external () |
Get the internal / external state. More... | |
void | _set_dlpf_filter (uint16_t frequency_hz) |
void | _set_sample_rate (unsigned desired_sample_rate_hz) |
void | check_registers () |
Private Attributes | |
PX4Accelerometer | _px4_accel |
PX4Gyroscope | _px4_gyro |
MPU9250_mag | _mag |
unsigned | _call_interval {1000} |
unsigned | _dlpf_freq {0} |
unsigned | _sample_rate {1000} |
perf_counter_t | _sample_perf |
perf_counter_t | _bad_transfers |
perf_counter_t | _bad_registers |
perf_counter_t | _good_transfers |
perf_counter_t | _duplicates |
uint8_t | _register_wait {0} |
uint64_t | _reset_wait {0} |
const uint16_t * | _checked_registers {nullptr} |
uint8_t | _checked_values [MPU9250_NUM_CHECKED_REGISTERS] {} |
uint8_t | _checked_bad [MPU9250_NUM_CHECKED_REGISTERS] {} |
unsigned | _checked_next {0} |
unsigned | _num_checked_registers {0} |
float | _last_temperature {0.0f} |
uint8_t | _last_accel_data [6] {} |
bool | _got_duplicate {false} |
Static Private Attributes | |
static constexpr int | MPU9250_NUM_CHECKED_REGISTERS {11} |
static const uint16_t | _mpu9250_checked_registers [MPU9250_NUM_CHECKED_REGISTERS] |
Friends | |
class | MPU9250_mag |
MPU9250::MPU9250 | ( | device::Device * | interface, |
device::Device * | mag_interface, | ||
enum Rotation | rotation | ||
) |
Definition at line 73 of file mpu9250.cpp.
References _px4_accel, _px4_gyro, DRV_ACC_DEVTYPE_MPU9250, DRV_GYR_DEVTYPE_MPU9250, PX4Accelerometer::set_device_type(), and PX4Gyroscope::set_device_type().
|
virtual |
Definition at line 90 of file mpu9250.cpp.
References _bad_registers, _bad_transfers, _duplicates, _good_transfers, _sample_perf, perf_free(), and stop().
|
private |
Definition at line 328 of file mpu9250.cpp.
References _dlpf_freq, _whoami, BITS_DLPF_CFG_10HZ, BITS_DLPF_CFG_184HZ, BITS_DLPF_CFG_20HZ, BITS_DLPF_CFG_250HZ, BITS_DLPF_CFG_3600HZ, BITS_DLPF_CFG_41HZ, BITS_DLPF_CFG_5HZ, BITS_DLPF_CFG_92HZ, MPU_WHOAMI_6500, MPU_WHOAMI_9250, MPUREG_CONFIG, and write_checked_reg().
Referenced by reset_mpu().
|
private |
Definition at line 295 of file mpu9250.cpp.
References _sample_rate, _whoami, MPU9250_GYRO_DEFAULT_RATE, MPU_WHOAMI_6500, MPU_WHOAMI_9250, MPUREG_SMPLRT_DIV, and write_checked_reg().
Referenced by reset_mpu().
|
private |
Definition at line 594 of file mpu9250.cpp.
References _duplicates, _got_duplicate, _last_accel_data, _sample_perf, perf_count(), and perf_end().
Referenced by measure().
|
private |
Definition at line 574 of file mpu9250.cpp.
References _bad_transfers, _good_transfers, _sample_perf, perf_count(), and perf_end().
Referenced by measure().
|
private |
Definition at line 514 of file mpu9250.cpp.
References _bad_registers, _checked_bad, _checked_next, _checked_registers, _checked_values, _num_checked_registers, _register_wait, _reset_wait, BIT_H_RESET, hrt_absolute_time(), MPU9250_HIGH_BUS_SPEED, MPU_CLK_SEL_AUTO, MPUREG_PWR_MGMT_1, MPUREG_PWR_MGMT_2, perf_count(), read_reg(), and write_reg().
Referenced by measure().
|
virtual |
Definition at line 104 of file mpu9250.cpp.
References MPU9250_mag::_interface, _interface, _mag, _reset_wait, _sample_rate, _whoami, MPU9250_mag::ak8963_reset(), device::Device::DeviceBusType_I2C, device::Device::get_device_bus_type(), hrt_absolute_time(), device::Device::init(), MPU9250_mag::is_passthrough(), MPU_WHOAMI_9250, OK, probe(), reset_mpu(), and start().
Referenced by DfMpu9250Wrapper::start(), and mpu9250::start_bus().
|
inlineprivate |
Get the internal / external state.
Definition at line 389 of file mpu9250.h.
References device::Device::external().
Referenced by MPU9250_mag::_measure().
|
private |
Fetch measurements from the sensor and update the report buffers.
Definition at line 619 of file mpu9250.cpp.
References _bad_registers, _bad_transfers, _last_temperature, _mag, MPU9250_mag::_measure(), _px4_accel, _px4_gyro, _register_wait, _reset_wait, _sample_perf, _whoami, check_duplicate(), check_null_data(), check_registers(), f(), hrt_absolute_time(), hrt_abstime, int16_t_from_bytes(), MPU9250_mag::is_passthrough(), MPU9250_mag::measure(), MPU9250_HIGH_BUS_SPEED, MPU_WHOAMI_6500, MPU_WHOAMI_9250, MPUREG_INT_STATUS, OK, perf_begin(), perf_end(), perf_event_count(), read_reg_range(), PX4Accelerometer::set_error_count(), PX4Gyroscope::set_error_count(), PX4Accelerometer::set_temperature(), PX4Gyroscope::set_temperature(), PX4Accelerometer::update(), and PX4Gyroscope::update().
Referenced by Run().
|
private |
Modify a checked register in the mpu.
Bits are cleared before bits are set.
reg | The register to modify. |
clearbits | Bits in the register to clear. |
setbits | Bits in the register to set. |
Definition at line 429 of file mpu9250.cpp.
References read_reg(), and write_checked_reg().
Referenced by MPU9250_mag::ak8963_setup(), and MPU9250_mag::ak8963_setup_master_i2c().
|
private |
Modify a register in the mpu.
Bits are cleared before bits are set.
reg | The register to modify. |
clearbits | Bits in the register to clear. |
setbits | Bits in the register to set. |
Definition at line 420 of file mpu9250.cpp.
References read_reg(), and write_reg().
Referenced by MPU9250_mag::ak8963_setup().
void MPU9250::print_info | ( | ) |
Diagnostics - print some basic information about the driver.
Definition at line 743 of file mpu9250.cpp.
References _bad_registers, _bad_transfers, _duplicates, _good_transfers, _mag, _px4_accel, _px4_gyro, _sample_perf, perf_print_counter(), PX4Accelerometer::print_status(), PX4Gyroscope::print_status(), and MPU9250_mag::print_status().
Referenced by mpu9250::status().
|
protectedvirtual |
whoami result
Definition at line 265 of file mpu9250.cpp.
References _checked_bad, _checked_registers, _checked_values, _mpu9250_checked_registers, _num_checked_registers, _whoami, MPU9250_NUM_CHECKED_REGISTERS, MPU_WHOAMI_6500, MPU_WHOAMI_9250, MPUREG_WHOAMI, and read_reg().
Referenced by init().
|
private |
Read a register from the mpu.
The | register to read. |
The | bus speed to read with. |
Definition at line 382 of file mpu9250.cpp.
References _interface, MPU9250_SET_SPEED, and device::Device::read().
Referenced by check_registers(), modify_checked_reg(), modify_reg(), probe(), and reset_mpu().
|
private |
Definition at line 402 of file mpu9250.cpp.
References _interface, arraySize, MPU9250_LOW_SPEED_OP, and device::Device::read().
|
private |
Read a register range from the mpu.
The | start address to read from. |
The | bus speed to read with. |
The | address of the target data buffer. |
The | count of bytes to be read. |
Definition at line 392 of file mpu9250.cpp.
References _interface, MPU9250_SET_SPEED, and device::Device::read().
Referenced by measure().
|
private |
Definition at line 157 of file mpu9250.cpp.
References _mag, _reset_wait, _whoami, MPU9250_mag::ak8963_reset(), hrt_absolute_time(), MPU_WHOAMI_9250, OK, and reset_mpu().
|
private |
Resets the main chip (excluding the magnetometer if any).
Definition at line 182 of file mpu9250.cpp.
References _checked_registers, _checked_values, _interface, _mag, _num_checked_registers, _px4_gyro, _sample_rate, _set_dlpf_filter(), _set_sample_rate(), _whoami, ACCEL_RANGE_G, BIT_H_RESET, BIT_I2C_IF_DIS, BIT_INT_ANYRD_2CLEAR, BIT_INT_BYPASS_EN, BIT_RAW_RDY_EN, BITS_ACCEL_CONFIG2_41HZ, BITS_FS_2000DPS, device::Device::DeviceBusType_I2C, device::Device::get_device_bus_type(), MPU9250_mag::is_passthrough(), MPU9250_DEFAULT_ONCHIP_FILTER_FREQ, MPU_CLK_SEL_AUTO, MPU_WHOAMI_6500, MPU_WHOAMI_9250, MPUREG_ACCEL_CONFIG2, MPUREG_GYRO_CONFIG, MPUREG_INT_ENABLE, MPUREG_INT_PIN_CFG, MPUREG_PWR_MGMT_1, MPUREG_PWR_MGMT_2, MPUREG_USER_CTRL, OK, read_reg(), set_accel_range(), PX4Gyroscope::set_scale(), write_checked_reg(), and write_reg().
Referenced by init(), and reset().
|
overrideprotected |
Definition at line 507 of file mpu9250.cpp.
References measure().
|
private |
Set the mpu measurement range.
max_g | The maximum G value the range must support. |
Definition at line 452 of file mpu9250.cpp.
References _px4_accel, _whoami, CONSTANTS_ONE_G, MPU_WHOAMI_6500, MPU_WHOAMI_9250, MPUREG_ACCEL_CONFIG, OK, PX4Accelerometer::set_scale(), and write_checked_reg().
Referenced by reset_mpu().
|
private |
Definition at line 492 of file mpu9250.cpp.
References _call_interval, MPU9250_TIMER_REDUCTION, and stop().
Referenced by init(), and DfMpu9250Wrapper::start().
|
private |
Definition at line 501 of file mpu9250.cpp.
Referenced by start(), DfMpu9250Wrapper::stop(), and ~MPU9250().
|
inlineprivate |
|
private |
Write a register in the mpu, updating _checked_values.
reg | The register to write. |
value | The new value to write. |
Definition at line 438 of file mpu9250.cpp.
References _checked_bad, _checked_registers, _checked_values, _num_checked_registers, and write_reg().
Referenced by _set_dlpf_filter(), _set_sample_rate(), modify_checked_reg(), reset_mpu(), and set_accel_range().
|
private |
Write a register in the mpu.
reg | The register to write. |
value | The new value to write. |
Definition at line 413 of file mpu9250.cpp.
References _interface, MPU9250_LOW_SPEED_OP, and device::Device::write().
Referenced by MPU9250_mag::ak8963_setup(), MPU9250_mag::ak8963_setup_master_i2c(), check_registers(), modify_reg(), MPU9250_mag::passthrough_read(), MPU9250_mag::passthrough_write(), reset_mpu(), MPU9250_mag::set_passthrough(), and write_checked_reg().
|
friend |
|
private |
Definition at line 265 of file mpu9250.h.
Referenced by check_registers(), measure(), print_info(), and ~MPU9250().
|
private |
Definition at line 264 of file mpu9250.h.
Referenced by check_null_data(), measure(), print_info(), and ~MPU9250().
|
private |
|
private |
Definition at line 282 of file mpu9250.h.
Referenced by check_registers(), probe(), and write_checked_reg().
|
private |
Definition at line 283 of file mpu9250.h.
Referenced by check_registers().
|
private |
Definition at line 279 of file mpu9250.h.
Referenced by check_registers(), probe(), reset_mpu(), and write_checked_reg().
|
private |
Definition at line 281 of file mpu9250.h.
Referenced by check_registers(), probe(), reset_mpu(), and write_checked_reg().
|
private |
Definition at line 259 of file mpu9250.h.
Referenced by _set_dlpf_filter().
|
private |
Definition at line 267 of file mpu9250.h.
Referenced by check_duplicate(), print_info(), and ~MPU9250().
|
private |
Definition at line 266 of file mpu9250.h.
Referenced by check_null_data(), print_info(), and ~MPU9250().
|
private |
Definition at line 295 of file mpu9250.h.
Referenced by check_duplicate().
|
protected |
Definition at line 241 of file mpu9250.h.
Referenced by init(), MPU9250_mag::read_block(), read_reg(), read_reg16(), read_reg_range(), reset_mpu(), and write_reg().
|
private |
Definition at line 294 of file mpu9250.h.
Referenced by check_duplicate().
|
private |
Definition at line 288 of file mpu9250.h.
Referenced by MPU9250_mag::_measure(), and measure().
|
private |
Definition at line 255 of file mpu9250.h.
Referenced by init(), measure(), print_info(), reset(), and reset_mpu().
|
staticprivate |
|
private |
Definition at line 284 of file mpu9250.h.
Referenced by check_registers(), probe(), reset_mpu(), and write_checked_reg().
|
private |
Definition at line 252 of file mpu9250.h.
Referenced by measure(), MPU9250(), print_info(), and set_accel_range().
|
private |
Definition at line 253 of file mpu9250.h.
Referenced by measure(), MPU9250(), print_info(), and reset_mpu().
|
private |
Definition at line 269 of file mpu9250.h.
Referenced by check_registers(), and measure().
|
private |
|
private |
Definition at line 263 of file mpu9250.h.
Referenced by check_duplicate(), check_null_data(), measure(), print_info(), and ~MPU9250().
|
private |
Definition at line 261 of file mpu9250.h.
Referenced by _set_sample_rate(), init(), and reset_mpu().
|
protected |
Definition at line 242 of file mpu9250.h.
Referenced by _set_dlpf_filter(), _set_sample_rate(), MPU9250_mag::ak8963_setup(), MPU9250_mag::ak8963_setup_master_i2c(), init(), measure(), probe(), reset(), reset_mpu(), and set_accel_range().
|
staticprivate |