AP_InertialSensor: fixed MPU6000_SPI bus initialisation

we need _spi for get_semaphore()
This commit is contained in:
Andrew Tridgell 2015-07-10 16:19:30 +10:00
parent 266857c595
commit 6df33dd3f4
2 changed files with 8 additions and 1 deletions

View File

@ -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

View File

@ -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);