From 6df33dd3f4eadc244ecab3945ccbe17292982c9f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 10 Jul 2015 16:19:30 +1000 Subject: [PATCH] AP_InertialSensor: fixed MPU6000_SPI bus initialisation we need _spi for get_semaphore() --- libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp | 8 +++++++- libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h | 1 + 2 files changed, 8 insertions(+), 1 deletion(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp index d2fae8eb2e..72132415a0 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp @@ -173,12 +173,18 @@ extern const AP_HAL::HAL& hal; #define HAL_INS_MPU60XX_I2C_ADDR 0x68 #endif + /* SPI bus driver implementation */ + +AP_MPU6000_BusDriver_SPI::AP_MPU6000_BusDriver_SPI(void) +{ + _spi = hal.spi->device(AP_HAL::SPIDevice_MPU6000); +} + void AP_MPU6000_BusDriver_SPI::init(bool &fifo_mode, uint8_t &max_samples) { fifo_mode = false; _error_count = 0; - _spi = hal.spi->device(AP_HAL::SPIDevice_MPU6000); // Disable I2C bus if SPI selected (Recommended in Datasheet write8(MPUREG_USER_CTRL, BIT_USER_CTRL_I2C_IF_DIS); /* maximum number of samples read by a burst diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h index 3fc02cbbd9..52492cd73c 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h @@ -113,6 +113,7 @@ 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);