diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp index 31e0592119..4992734818 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp @@ -18,138 +18,137 @@ extern const AP_HAL::HAL& hal; #endif // MPU 6000 registers -#define MPUREG_XG_OFFS_TC 0x00 -#define MPUREG_YG_OFFS_TC 0x01 -#define MPUREG_ZG_OFFS_TC 0x02 -#define MPUREG_X_FINE_GAIN 0x03 -#define MPUREG_Y_FINE_GAIN 0x04 -#define MPUREG_Z_FINE_GAIN 0x05 -#define MPUREG_XA_OFFS_H 0x06 // X axis accelerometer offset (high byte) -#define MPUREG_XA_OFFS_L 0x07 // X axis accelerometer offset (low byte) -#define MPUREG_YA_OFFS_H 0x08 // Y axis accelerometer offset (high byte) -#define MPUREG_YA_OFFS_L 0x09 // Y axis accelerometer offset (low byte) -#define MPUREG_ZA_OFFS_H 0x0A // Z axis accelerometer offset (high byte) -#define MPUREG_ZA_OFFS_L 0x0B // Z axis accelerometer offset (low byte) -#define MPUREG_PRODUCT_ID 0x0C // Product ID Register +#define MPUREG_XG_OFFS_TC 0x00 +#define MPUREG_YG_OFFS_TC 0x01 +#define MPUREG_ZG_OFFS_TC 0x02 +#define MPUREG_X_FINE_GAIN 0x03 +#define MPUREG_Y_FINE_GAIN 0x04 +#define MPUREG_Z_FINE_GAIN 0x05 +#define MPUREG_XA_OFFS_H 0x06 // X axis accelerometer offset (high byte) +#define MPUREG_XA_OFFS_L 0x07 // X axis accelerometer offset (low byte) +#define MPUREG_YA_OFFS_H 0x08 // Y axis accelerometer offset (high byte) +#define MPUREG_YA_OFFS_L 0x09 // Y axis accelerometer offset (low byte) +#define MPUREG_ZA_OFFS_H 0x0A // Z axis accelerometer offset (high byte) +#define MPUREG_ZA_OFFS_L 0x0B // Z axis accelerometer offset (low byte) +#define MPUREG_PRODUCT_ID 0x0C // Product ID Register #define MPUREG_XG_OFFS_USRH 0x13 // X axis gyro offset (high byte) #define MPUREG_XG_OFFS_USRL 0x14 // X axis gyro offset (low byte) #define MPUREG_YG_OFFS_USRH 0x15 // Y axis gyro offset (high byte) #define MPUREG_YG_OFFS_USRL 0x16 // Y axis gyro offset (low byte) #define MPUREG_ZG_OFFS_USRH 0x17 // Z axis gyro offset (high byte) #define MPUREG_ZG_OFFS_USRL 0x18 // Z axis gyro offset (low byte) -#define MPUREG_SMPLRT_DIV 0x19 // sample rate. Fsample= 1Khz/(+1) = 200Hz -# define MPUREG_SMPLRT_1000HZ 0x00 -# define MPUREG_SMPLRT_500HZ 0x01 -# define MPUREG_SMPLRT_250HZ 0x03 -# define MPUREG_SMPLRT_200HZ 0x04 -# define MPUREG_SMPLRT_100HZ 0x09 -# define MPUREG_SMPLRT_50HZ 0x13 -#define MPUREG_CONFIG 0x1A -#define MPUREG_GYRO_CONFIG 0x1B +#define MPUREG_SMPLRT_DIV 0x19 // sample rate. Fsample= 1Khz/(+1) = 200Hz +# define MPUREG_SMPLRT_1000HZ 0x00 +# define MPUREG_SMPLRT_500HZ 0x01 +# define MPUREG_SMPLRT_250HZ 0x03 +# define MPUREG_SMPLRT_200HZ 0x04 +# define MPUREG_SMPLRT_100HZ 0x09 +# define MPUREG_SMPLRT_50HZ 0x13 +#define MPUREG_CONFIG 0x1A +#define MPUREG_GYRO_CONFIG 0x1B // bit definitions for MPUREG_GYRO_CONFIG -# define BITS_GYRO_FS_250DPS 0x00 -# define BITS_GYRO_FS_500DPS 0x08 -# define BITS_GYRO_FS_1000DPS 0x10 -# define BITS_GYRO_FS_2000DPS 0x18 -# define BITS_GYRO_FS_MASK 0x18 // only bits 3 and 4 are used for gyro full scale so use this to mask off other bits -# define BITS_GYRO_ZGYRO_SELFTEST 0x20 -# define BITS_GYRO_YGYRO_SELFTEST 0x40 -# define BITS_GYRO_XGYRO_SELFTEST 0x80 -#define MPUREG_ACCEL_CONFIG 0x1C -#define MPUREG_MOT_THR 0x1F // detection threshold for Motion interrupt generation. Motion is detected when the absolute value of any of the accelerometer measurements exceeds this -#define MPUREG_MOT_DUR 0x20 // duration counter threshold for Motion interrupt generation. The duration counter ticks at 1 kHz, therefore MOT_DUR has a unit of 1 LSB = 1 ms -#define MPUREG_ZRMOT_THR 0x21 // detection threshold for Zero Motion interrupt generation. -#define MPUREG_ZRMOT_DUR 0x22 // duration counter threshold for Zero Motion interrupt generation. The duration counter ticks at 16 Hz, therefore ZRMOT_DUR has a unit of 1 LSB = 64 ms. -#define MPUREG_FIFO_EN 0x23 -# define BIT_TEMP_FIFO_EN 0x80 -# define BIT_XG_FIFO_EN 0x40 -# define BIT_YG_FIFO_EN 0x20 -# define BIT_ZG_FIFO_EN 0x10 -# define BIT_ACCEL_FIFO_EN 0x08 -# define BIT_SLV2_FIFO_EN 0x04 -# define BIT_SLV1_FIFO_EN 0x02 -# define BIT_SLV0_FIFI_EN0 0x01 -#define MPUREG_INT_PIN_CFG 0x37 -# define BIT_INT_RD_CLEAR 0x10 // clear the interrupt when any read occurs -# define BIT_LATCH_INT_EN 0x20 // latch data ready pin -#define MPUREG_INT_ENABLE 0x38 +# define BITS_GYRO_FS_250DPS 0x00 +# define BITS_GYRO_FS_500DPS 0x08 +# define BITS_GYRO_FS_1000DPS 0x10 +# define BITS_GYRO_FS_2000DPS 0x18 +# define BITS_GYRO_FS_MASK 0x18 // only bits 3 and 4 are used for gyro full scale so use this to mask off other bits +# define BITS_GYRO_ZGYRO_SELFTEST 0x20 +# define BITS_GYRO_YGYRO_SELFTEST 0x40 +# define BITS_GYRO_XGYRO_SELFTEST 0x80 +#define MPUREG_ACCEL_CONFIG 0x1C +#define MPUREG_MOT_THR 0x1F // detection threshold for Motion interrupt generation. Motion is detected when the absolute value of any of the accelerometer measurements exceeds this +#define MPUREG_MOT_DUR 0x20 // duration counter threshold for Motion interrupt generation. The duration counter ticks at 1 kHz, therefore MOT_DUR has a unit of 1 LSB = 1 ms +#define MPUREG_ZRMOT_THR 0x21 // detection threshold for Zero Motion interrupt generation. +#define MPUREG_ZRMOT_DUR 0x22 // duration counter threshold for Zero Motion interrupt generation. The duration counter ticks at 16 Hz, therefore ZRMOT_DUR has a unit of 1 LSB = 64 ms. +#define MPUREG_FIFO_EN 0x23 +# define BIT_TEMP_FIFO_EN 0x80 +# define BIT_XG_FIFO_EN 0x40 +# define BIT_YG_FIFO_EN 0x20 +# define BIT_ZG_FIFO_EN 0x10 +# define BIT_ACCEL_FIFO_EN 0x08 +# define BIT_SLV2_FIFO_EN 0x04 +# define BIT_SLV1_FIFO_EN 0x02 +# define BIT_SLV0_FIFI_EN0 0x01 +#define MPUREG_INT_PIN_CFG 0x37 +# define BIT_INT_RD_CLEAR 0x10 // clear the interrupt when any read occurs +# define BIT_LATCH_INT_EN 0x20 // latch data ready pin +#define MPUREG_INT_ENABLE 0x38 // bit definitions for MPUREG_INT_ENABLE -# define BIT_RAW_RDY_EN 0x01 -# define BIT_DMP_INT_EN 0x02 // enabling this bit (DMP_INT_EN) also enables RAW_RDY_EN it seems -# define BIT_UNKNOWN_INT_EN 0x04 -# define BIT_I2C_MST_INT_EN 0x08 -# define BIT_FIFO_OFLOW_EN 0x10 -# define BIT_ZMOT_EN 0x20 -# define BIT_MOT_EN 0x40 -# define BIT_FF_EN 0x80 -#define MPUREG_INT_STATUS 0x3A +# define BIT_RAW_RDY_EN 0x01 +# define BIT_DMP_INT_EN 0x02 // enabling this bit (DMP_INT_EN) also enables RAW_RDY_EN it seems +# define BIT_UNKNOWN_INT_EN 0x04 +# define BIT_I2C_MST_INT_EN 0x08 +# define BIT_FIFO_OFLOW_EN 0x10 +# define BIT_ZMOT_EN 0x20 +# define BIT_MOT_EN 0x40 +# define BIT_FF_EN 0x80 +#define MPUREG_INT_STATUS 0x3A // bit definitions for MPUREG_INT_STATUS (same bit pattern as above because this register shows what interrupt actually fired) -# define BIT_RAW_RDY_INT 0x01 -# define BIT_DMP_INT 0x02 -# define BIT_UNKNOWN_INT 0x04 -# define BIT_I2C_MST_INT 0x08 -# define BIT_FIFO_OFLOW_INT 0x10 -# define BIT_ZMOT_INT 0x20 -# define BIT_MOT_INT 0x40 -# define BIT_FF_INT 0x80 -#define MPUREG_ACCEL_XOUT_H 0x3B -#define MPUREG_ACCEL_XOUT_L 0x3C -#define MPUREG_ACCEL_YOUT_H 0x3D -#define MPUREG_ACCEL_YOUT_L 0x3E -#define MPUREG_ACCEL_ZOUT_H 0x3F -#define MPUREG_ACCEL_ZOUT_L 0x40 -#define MPUREG_TEMP_OUT_H 0x41 -#define MPUREG_TEMP_OUT_L 0x42 -#define MPUREG_GYRO_XOUT_H 0x43 -#define MPUREG_GYRO_XOUT_L 0x44 -#define MPUREG_GYRO_YOUT_H 0x45 -#define MPUREG_GYRO_YOUT_L 0x46 -#define MPUREG_GYRO_ZOUT_H 0x47 -#define MPUREG_GYRO_ZOUT_L 0x48 -#define MPUREG_USER_CTRL 0x6A +# define BIT_RAW_RDY_INT 0x01 +# define BIT_DMP_INT 0x02 +# define BIT_UNKNOWN_INT 0x04 +# define BIT_I2C_MST_INT 0x08 +# define BIT_FIFO_OFLOW_INT 0x10 +# define BIT_ZMOT_INT 0x20 +# define BIT_MOT_INT 0x40 +# define BIT_FF_INT 0x80 +#define MPUREG_ACCEL_XOUT_H 0x3B +#define MPUREG_ACCEL_XOUT_L 0x3C +#define MPUREG_ACCEL_YOUT_H 0x3D +#define MPUREG_ACCEL_YOUT_L 0x3E +#define MPUREG_ACCEL_ZOUT_H 0x3F +#define MPUREG_ACCEL_ZOUT_L 0x40 +#define MPUREG_TEMP_OUT_H 0x41 +#define MPUREG_TEMP_OUT_L 0x42 +#define MPUREG_GYRO_XOUT_H 0x43 +#define MPUREG_GYRO_XOUT_L 0x44 +#define MPUREG_GYRO_YOUT_H 0x45 +#define MPUREG_GYRO_YOUT_L 0x46 +#define MPUREG_GYRO_ZOUT_H 0x47 +#define MPUREG_GYRO_ZOUT_L 0x48 +#define MPUREG_USER_CTRL 0x6A // bit definitions for MPUREG_USER_CTRL -# define BIT_USER_CTRL_SIG_COND_RESET 0x01 // resets signal paths and results registers for all sensors (gyros, accel, temp) -# define BIT_USER_CTRL_I2C_MST_RESET 0x02 // reset I2C Master (only applicable if I2C_MST_EN bit is set) -# define BIT_USER_CTRL_FIFO_RESET 0x04 // Reset (i.e. clear) FIFO buffer -# define BIT_USER_CTRL_DMP_RESET 0x08 // Reset DMP -# define BIT_USER_CTRL_I2C_IF_DIS 0x10 // Disable primary I2C interface and enable hal.spi->interface -# define BIT_USER_CTRL_I2C_MST_EN 0x20 // Enable MPU to act as the I2C Master to external slave sensors -# define BIT_USER_CTRL_FIFO_EN 0x40 // Enable FIFO operations -# define BIT_USER_CTRL_DMP_EN 0x80 // Enable DMP operations -#define MPUREG_PWR_MGMT_1 0x6B -# define BIT_PWR_MGMT_1_CLK_INTERNAL 0x00 // clock set to internal 8Mhz oscillator -# define BIT_PWR_MGMT_1_CLK_XGYRO 0x01 // PLL with X axis gyroscope reference -# define BIT_PWR_MGMT_1_CLK_YGYRO 0x02 // PLL with Y axis gyroscope reference -# define BIT_PWR_MGMT_1_CLK_ZGYRO 0x03 // PLL with Z axis gyroscope reference -# define BIT_PWR_MGMT_1_CLK_EXT32KHZ 0x04 // PLL with external 32.768kHz reference -# define BIT_PWR_MGMT_1_CLK_EXT19MHZ 0x05 // PLL with external 19.2MHz reference -# define BIT_PWR_MGMT_1_CLK_STOP 0x07 // Stops the clock and keeps the timing generator in reset -# define BIT_PWR_MGMT_1_TEMP_DIS 0x08 // disable temperature sensor -# define BIT_PWR_MGMT_1_CYCLE 0x20 // put sensor into cycle mode. cycles between sleep mode and waking up to take a single sample of data from active sensors at a rate determined by LP_WAKE_CTRL -# define BIT_PWR_MGMT_1_SLEEP 0x40 // put sensor into low power sleep mode -# define BIT_PWR_MGMT_1_DEVICE_RESET 0x80 // reset entire device -#define MPUREG_PWR_MGMT_2 0x6C // allows the user to configure the frequency of wake-ups in Accelerometer Only Low Power Mode -#define MPUREG_BANK_SEL 0x6D // DMP bank selection register (used to indirectly access DMP registers) -#define MPUREG_MEM_START_ADDR 0x6E // DMP memory start address (used to indirectly write to dmp memory) -#define MPUREG_MEM_R_W 0x6F // DMP related register -#define MPUREG_DMP_CFG_1 0x70 // DMP related register -#define MPUREG_DMP_CFG_2 0x71 // DMP related register -#define MPUREG_FIFO_COUNTH 0x72 -#define MPUREG_FIFO_COUNTL 0x73 -#define MPUREG_FIFO_R_W 0x74 -#define MPUREG_WHOAMI 0x75 - +# define BIT_USER_CTRL_SIG_COND_RESET 0x01 // resets signal paths and results registers for all sensors (gyros, accel, temp) +# define BIT_USER_CTRL_I2C_MST_RESET 0x02 // reset I2C Master (only applicable if I2C_MST_EN bit is set) +# define BIT_USER_CTRL_FIFO_RESET 0x04 // Reset (i.e. clear) FIFO buffer +# define BIT_USER_CTRL_DMP_RESET 0x08 // Reset DMP +# define BIT_USER_CTRL_I2C_IF_DIS 0x10 // Disable primary I2C interface and enable hal.spi->interface +# define BIT_USER_CTRL_I2C_MST_EN 0x20 // Enable MPU to act as the I2C Master to external slave sensors +# define BIT_USER_CTRL_FIFO_EN 0x40 // Enable FIFO operations +# define BIT_USER_CTRL_DMP_EN 0x80 // Enable DMP operations +#define MPUREG_PWR_MGMT_1 0x6B +# define BIT_PWR_MGMT_1_CLK_INTERNAL 0x00 // clock set to internal 8Mhz oscillator +# define BIT_PWR_MGMT_1_CLK_XGYRO 0x01 // PLL with X axis gyroscope reference +# define BIT_PWR_MGMT_1_CLK_YGYRO 0x02 // PLL with Y axis gyroscope reference +# define BIT_PWR_MGMT_1_CLK_ZGYRO 0x03 // PLL with Z axis gyroscope reference +# define BIT_PWR_MGMT_1_CLK_EXT32KHZ 0x04 // PLL with external 32.768kHz reference +# define BIT_PWR_MGMT_1_CLK_EXT19MHZ 0x05 // PLL with external 19.2MHz reference +# define BIT_PWR_MGMT_1_CLK_STOP 0x07 // Stops the clock and keeps the timing generator in reset +# define BIT_PWR_MGMT_1_TEMP_DIS 0x08 // disable temperature sensor +# define BIT_PWR_MGMT_1_CYCLE 0x20 // put sensor into cycle mode. cycles between sleep mode and waking up to take a single sample of data from active sensors at a rate determined by LP_WAKE_CTRL +# define BIT_PWR_MGMT_1_SLEEP 0x40 // put sensor into low power sleep mode +# define BIT_PWR_MGMT_1_DEVICE_RESET 0x80 // reset entire device +#define MPUREG_PWR_MGMT_2 0x6C // allows the user to configure the frequency of wake-ups in Accelerometer Only Low Power Mode +#define MPUREG_BANK_SEL 0x6D // DMP bank selection register (used to indirectly access DMP registers) +#define MPUREG_MEM_START_ADDR 0x6E // DMP memory start address (used to indirectly write to dmp memory) +#define MPUREG_MEM_R_W 0x6F // DMP related register +#define MPUREG_DMP_CFG_1 0x70 // DMP related register +#define MPUREG_DMP_CFG_2 0x71 // DMP related register +#define MPUREG_FIFO_COUNTH 0x72 +#define MPUREG_FIFO_COUNTL 0x73 +#define MPUREG_FIFO_R_W 0x74 +#define MPUREG_WHOAMI 0x75 // Configuration bits MPU 3000 and MPU 6000 (not revised)? #define BITS_DLPF_CFG_256HZ_NOLPF2 0x00 -#define BITS_DLPF_CFG_188HZ 0x01 -#define BITS_DLPF_CFG_98HZ 0x02 -#define BITS_DLPF_CFG_42HZ 0x03 -#define BITS_DLPF_CFG_20HZ 0x04 -#define BITS_DLPF_CFG_10HZ 0x05 -#define BITS_DLPF_CFG_5HZ 0x06 +#define BITS_DLPF_CFG_188HZ 0x01 +#define BITS_DLPF_CFG_98HZ 0x02 +#define BITS_DLPF_CFG_42HZ 0x03 +#define BITS_DLPF_CFG_20HZ 0x04 +#define BITS_DLPF_CFG_10HZ 0x05 +#define BITS_DLPF_CFG_5HZ 0x06 #define BITS_DLPF_CFG_2100HZ_NOLPF 0x07 -#define BITS_DLPF_CFG_MASK 0x07 +#define BITS_DLPF_CFG_MASK 0x07 // Product ID Description for MPU6000 // high 4 bits low 4 bits diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h index 52492cd73c..7e613f08f8 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h @@ -30,18 +30,18 @@ class AP_MPU6000_BusDriver { - public: - virtual void init(bool &fifo_mode, uint8_t &max_samples) = 0; - virtual void read8(uint8_t reg, uint8_t *val) = 0; - virtual void write8(uint8_t reg, uint8_t val) = 0; - enum bus_speed { - SPEED_LOW, SPEED_HIGH - }; - virtual void set_bus_speed(AP_HAL::SPIDeviceDriver::bus_speed speed) = 0; - virtual void read_burst(uint8_t* samples, - AP_HAL::DigitalSource *_drdy_pin, - uint8_t &n_samples) = 0; - virtual AP_HAL::Semaphore* get_semaphore() = 0; +public: + virtual void init(bool &fifo_mode, uint8_t &max_samples) = 0; + virtual void read8(uint8_t reg, uint8_t *val) = 0; + virtual void write8(uint8_t reg, uint8_t val) = 0; + enum bus_speed { + SPEED_LOW, SPEED_HIGH + }; + virtual void set_bus_speed(AP_HAL::SPIDeviceDriver::bus_speed speed) = 0; + virtual void read_burst(uint8_t* samples, + AP_HAL::DigitalSource *_drdy_pin, + uint8_t &n_samples) = 0; + virtual AP_HAL::Semaphore* get_semaphore() = 0; }; class AP_InertialSensor_MPU6000 : public AP_InertialSensor_Backend @@ -67,21 +67,21 @@ private: uint8_t _accel_instance; AP_HAL::DigitalSource *_drdy_pin; - bool _init_sensor(void); - bool _sample_available(); - void _read_data_transaction(); - bool _data_ready(); - void _poll_data(void); - uint8_t _register_read( uint8_t reg); - void _register_write( uint8_t reg, uint8_t val ); - void _register_write_check(uint8_t reg, uint8_t val); - bool _hardware_init(void); - void _accumulate(uint8_t *samples, uint8_t n_samples); + bool _init_sensor(void); + bool _sample_available(); + void _read_data_transaction(); + bool _data_ready(); + void _poll_data(void); + uint8_t _register_read( uint8_t reg); + void _register_write( uint8_t reg, uint8_t val ); + void _register_write_check(uint8_t reg, uint8_t val); + bool _hardware_init(void); + void _accumulate(uint8_t *samples, uint8_t n_samples); AP_MPU6000_BusDriver *_bus; AP_HAL::Semaphore *_bus_sem; - static const float _gyro_scale; + static const float _gyro_scale; // support for updating filter at runtime int8_t _last_accel_filter_hz; @@ -96,7 +96,7 @@ private: Vector3f _accel_filtered; Vector3f _gyro_filtered; - // Low Pass filters for gyro and accel + // Low Pass filters for gyro and accel LowPassFilter2pVector3f _accel_filter; LowPassFilter2pVector3f _gyro_filter; #else @@ -112,42 +112,42 @@ private: class AP_MPU6000_BusDriver_SPI : public AP_MPU6000_BusDriver { - public: - AP_MPU6000_BusDriver_SPI(void); - void init(bool &fifo_mode, uint8_t &max_samples); - void read8(uint8_t reg, uint8_t *val); - void write8(uint8_t reg, uint8_t val); - void set_bus_speed(AP_HAL::SPIDeviceDriver::bus_speed speed); - void read_burst(uint8_t* samples, - AP_HAL::DigitalSource *_drdy_pin, - uint8_t &n_samples); - AP_HAL::Semaphore* get_semaphore(); +public: + AP_MPU6000_BusDriver_SPI(void); + void init(bool &fifo_mode, uint8_t &max_samples); + void read8(uint8_t reg, uint8_t *val); + void write8(uint8_t reg, uint8_t val); + void set_bus_speed(AP_HAL::SPIDeviceDriver::bus_speed speed); + void read_burst(uint8_t* samples, + AP_HAL::DigitalSource *_drdy_pin, + uint8_t &n_samples); + AP_HAL::Semaphore* get_semaphore(); - private: - AP_HAL::SPIDeviceDriver *_spi; - AP_HAL::Semaphore *_spi_sem; - // count of bus errors - uint16_t _error_count; +private: + AP_HAL::SPIDeviceDriver *_spi; + AP_HAL::Semaphore *_spi_sem; + // count of bus errors + uint16_t _error_count; }; class AP_MPU6000_BusDriver_I2C : public AP_MPU6000_BusDriver { - public: - AP_MPU6000_BusDriver_I2C(AP_HAL::I2CDriver *i2c, uint8_t addr); - void init(bool &fifo_mode, uint8_t &max_samples); - void read8(uint8_t reg, uint8_t *val); - void write8(uint8_t reg, uint8_t val); - void set_bus_speed(AP_HAL::SPIDeviceDriver::bus_speed speed); - void read_burst(uint8_t* samples, - AP_HAL::DigitalSource *_drdy_pin, - uint8_t &n_samples); - AP_HAL::Semaphore* get_semaphore(); +public: + AP_MPU6000_BusDriver_I2C(AP_HAL::I2CDriver *i2c, uint8_t addr); + void init(bool &fifo_mode, uint8_t &max_samples); + void read8(uint8_t reg, uint8_t *val); + void write8(uint8_t reg, uint8_t val); + void set_bus_speed(AP_HAL::SPIDeviceDriver::bus_speed speed); + void read_burst(uint8_t* samples, + AP_HAL::DigitalSource *_drdy_pin, + uint8_t &n_samples); + AP_HAL::Semaphore* get_semaphore(); - private: - uint8_t _addr; - AP_HAL::I2CDriver *_i2c; - AP_HAL::Semaphore *_i2c_sem; - uint8_t _rx[MAX_DATA_READ]; +private: + uint8_t _addr; + AP_HAL::I2CDriver *_i2c; + AP_HAL::Semaphore *_i2c_sem; + uint8_t _rx[MAX_DATA_READ]; }; #endif // __AP_INERTIAL_SENSOR_MPU6000_H__