diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index afa28d9939..987f1cd8bc 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -403,7 +403,7 @@ AP_InertialSensor::_detect_backends(void) #elif HAL_INS_DEFAULT == HAL_INS_MPU60XX_SPI _add_backend(AP_InertialSensor_MPU6000::detect_spi(*this)); #elif HAL_INS_DEFAULT == HAL_INS_MPU60XX_I2C && HAL_INS_MPU60XX_I2C_BUS == 2 - _add_backend(AP_InertialSensor_MPU6000::detect_i2c2(*this)); + _add_backend(AP_InertialSensor_MPU6000::detect_i2c(*this, hal.i2c2, HAL_INS_MPU60XX_I2C_ADDR)); #elif HAL_INS_DEFAULT == HAL_INS_PX4 || HAL_INS_DEFAULT == HAL_INS_VRBRAIN _add_backend(AP_InertialSensor_PX4::detect(*this)); #elif HAL_INS_DEFAULT == HAL_INS_OILPAN diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp index 4b43fe1018..db95be4419 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp @@ -168,11 +168,6 @@ extern const AP_HAL::HAL& hal; #define int16_val(v, idx) ((int16_t)(((uint16_t)v[2*idx] << 8) | v[2*idx+1])) #define uint16_val(v, idx)(((uint16_t)v[2*idx] << 8) | v[2*idx+1]) -#if !defined(HAL_INS_MPU60XX_I2C_ADDR) -#define HAL_INS_MPU60XX_I2C_ADDR 0x68 -#endif - - /* SPI bus driver implementation */ AP_MPU6000_BusDriver_SPI::AP_MPU6000_BusDriver_SPI(void) : @@ -416,10 +411,12 @@ AP_InertialSensor_Backend *AP_InertialSensor_MPU6000::detect_spi(AP_InertialSens return sensor; } -AP_InertialSensor_Backend *AP_InertialSensor_MPU6000::detect_i2c2(AP_InertialSensor &_imu) +AP_InertialSensor_Backend *AP_InertialSensor_MPU6000::detect_i2c(AP_InertialSensor &_imu, + AP_HAL::I2CDriver *i2c, + uint8_t addr) { AP_InertialSensor_MPU6000 *sensor = new AP_InertialSensor_MPU6000(_imu, - new AP_MPU6000_BusDriver_I2C(hal.i2c2, HAL_INS_MPU60XX_I2C_ADDR)); + new AP_MPU6000_BusDriver_I2C(i2c, addr)); if (sensor == NULL) { return NULL; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h index 94c15c8be4..6056eaf299 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h @@ -45,7 +45,9 @@ class AP_InertialSensor_MPU6000 : public AP_InertialSensor_Backend { public: AP_InertialSensor_MPU6000(AP_InertialSensor &imu, AP_MPU6000_BusDriver *bus); - static AP_InertialSensor_Backend *detect_i2c2(AP_InertialSensor &_imu); + static AP_InertialSensor_Backend *detect_i2c(AP_InertialSensor &_imu, + AP_HAL::I2CDriver *i2c, + uint8_t addr); static AP_InertialSensor_Backend *detect_spi(AP_InertialSensor &_imu); /* update accel and gyro state */