Browse Source

AP_InertialSensor: fixed MPU6000_SPI bus initialisation

we need _spi for get_semaphore()
master
Andrew Tridgell 10 years ago
parent
commit
6df33dd3f4
  1. 8
      libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp
  2. 1
      libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h

8
libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp

@ -173,12 +173,18 @@ extern const AP_HAL::HAL& hal; @@ -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

1
libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h

@ -113,6 +113,7 @@ private: @@ -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);

Loading…
Cancel
Save