AP_InertialSensor: implement device IDs for MPU6000 and MPU9250 AuxilaryBus
This commit is contained in:
parent
ac2c25539b
commit
64a5d3938c
@ -314,7 +314,7 @@ void AP_InertialSensor_MPU6000::_fifo_enable()
|
||||
|
||||
bool AP_InertialSensor_MPU6000::_has_auxiliary_bus()
|
||||
{
|
||||
return _dev->bus_type != AP_HAL::Device::BUS_TYPE_I2C;
|
||||
return _dev->bus_type() != AP_HAL::Device::BUS_TYPE_I2C;
|
||||
}
|
||||
|
||||
void AP_InertialSensor_MPU6000::start()
|
||||
@ -416,7 +416,7 @@ AuxiliaryBus *AP_InertialSensor_MPU6000::get_auxiliary_bus()
|
||||
}
|
||||
|
||||
if (_has_auxiliary_bus()) {
|
||||
_auxiliary_bus = new AP_MPU6000_AuxiliaryBus(*this);
|
||||
_auxiliary_bus = new AP_MPU6000_AuxiliaryBus(*this, _dev->get_bus_id());
|
||||
}
|
||||
|
||||
return _auxiliary_bus;
|
||||
@ -647,7 +647,7 @@ bool AP_InertialSensor_MPU6000::_hardware_init(void)
|
||||
hal.scheduler->delay(100);
|
||||
|
||||
/* bus-dependent initialization */
|
||||
if (_dev->bus_type == AP_HAL::Device::BUS_TYPE_SPI) {
|
||||
if (_dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {
|
||||
/* Disable I2C bus if SPI selected (Recommended in Datasheet to be
|
||||
* done just after the device is reset) */
|
||||
_register_write(MPUREG_USER_CTRL, BIT_USER_CTRL_I2C_IF_DIS);
|
||||
@ -809,8 +809,8 @@ int AP_MPU6000_AuxiliaryBusSlave::read(uint8_t *buf)
|
||||
|
||||
/* MPU6000 provides up to 5 slave devices, but the 5th is way too different to
|
||||
* configure and is seldom used */
|
||||
AP_MPU6000_AuxiliaryBus::AP_MPU6000_AuxiliaryBus(AP_InertialSensor_MPU6000 &backend)
|
||||
: AuxiliaryBus(backend, 4)
|
||||
AP_MPU6000_AuxiliaryBus::AP_MPU6000_AuxiliaryBus(AP_InertialSensor_MPU6000 &backend, uint32_t devid)
|
||||
: AuxiliaryBus(backend, 4, devid)
|
||||
{
|
||||
}
|
||||
|
||||
|
@ -140,7 +140,7 @@ public:
|
||||
AP_HAL::Semaphore *get_semaphore() override;
|
||||
|
||||
protected:
|
||||
AP_MPU6000_AuxiliaryBus(AP_InertialSensor_MPU6000 &backend);
|
||||
AP_MPU6000_AuxiliaryBus(AP_InertialSensor_MPU6000 &backend, uint32_t devid);
|
||||
|
||||
AuxiliaryBusSlave *_instantiate_slave(uint8_t addr, uint8_t instance) override;
|
||||
int _configure_periodic_read(AuxiliaryBusSlave *slave, uint8_t reg,
|
||||
|
@ -274,7 +274,7 @@ bool AP_InertialSensor_MPU9250::_init()
|
||||
|
||||
bool AP_InertialSensor_MPU9250::_has_auxiliary_bus()
|
||||
{
|
||||
return _dev->bus_type != AP_HAL::Device::BUS_TYPE_I2C;
|
||||
return _dev->bus_type() != AP_HAL::Device::BUS_TYPE_I2C;
|
||||
}
|
||||
|
||||
void AP_InertialSensor_MPU9250::start()
|
||||
@ -347,7 +347,7 @@ AuxiliaryBus *AP_InertialSensor_MPU9250::get_auxiliary_bus()
|
||||
}
|
||||
|
||||
if (_has_auxiliary_bus()) {
|
||||
_auxiliary_bus = new AP_MPU9250_AuxiliaryBus(*this);
|
||||
_auxiliary_bus = new AP_MPU9250_AuxiliaryBus(*this, _dev->get_bus_id());
|
||||
}
|
||||
|
||||
return _auxiliary_bus;
|
||||
@ -464,7 +464,7 @@ bool AP_InertialSensor_MPU9250::_hardware_init(void)
|
||||
hal.scheduler->delay(100);
|
||||
|
||||
/* bus-dependent initialization */
|
||||
if (_dev->bus_type == AP_HAL::Device::BUS_TYPE_SPI) {
|
||||
if (_dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {
|
||||
/* Disable I2C bus if SPI selected (Recommended in Datasheet to be
|
||||
* done just after the device is reset) */
|
||||
_register_write(MPUREG_USER_CTRL, BIT_USER_CTRL_I2C_IF_DIS);
|
||||
@ -623,8 +623,8 @@ int AP_MPU9250_AuxiliaryBusSlave::read(uint8_t *buf)
|
||||
|
||||
/* MPU9250 provides up to 5 slave devices, but the 5th is way too different to
|
||||
* configure and is seldom used */
|
||||
AP_MPU9250_AuxiliaryBus::AP_MPU9250_AuxiliaryBus(AP_InertialSensor_MPU9250 &backend)
|
||||
: AuxiliaryBus(backend, 4)
|
||||
AP_MPU9250_AuxiliaryBus::AP_MPU9250_AuxiliaryBus(AP_InertialSensor_MPU9250 &backend, uint32_t devid)
|
||||
: AuxiliaryBus(backend, 4, devid)
|
||||
{
|
||||
}
|
||||
|
||||
|
@ -119,7 +119,7 @@ public:
|
||||
AP_HAL::Semaphore *get_semaphore() override;
|
||||
|
||||
protected:
|
||||
AP_MPU9250_AuxiliaryBus(AP_InertialSensor_MPU9250 &backend);
|
||||
AP_MPU9250_AuxiliaryBus(AP_InertialSensor_MPU9250 &backend, uint32_t devid);
|
||||
|
||||
AuxiliaryBusSlave *_instantiate_slave(uint8_t addr, uint8_t instance);
|
||||
int _configure_periodic_read(AuxiliaryBusSlave *slave, uint8_t reg,
|
||||
|
Loading…
Reference in New Issue
Block a user