diff --git a/libraries/AP_HAL/Device.h b/libraries/AP_HAL/Device.h index bf6fc8705e..b56a67932e 100644 --- a/libraries/AP_HAL/Device.h +++ b/libraries/AP_HAL/Device.h @@ -27,8 +27,8 @@ class AP_HAL::Device { public: enum BusType { - I2C, - SPI, + BUS_TYPE_I2C, + BUS_TYPE_SPI, }; enum Speed { diff --git a/libraries/AP_HAL/I2CDevice.h b/libraries/AP_HAL/I2CDevice.h index 68481872a4..278a7f0683 100644 --- a/libraries/AP_HAL/I2CDevice.h +++ b/libraries/AP_HAL/I2CDevice.h @@ -27,7 +27,7 @@ namespace AP_HAL { class I2CDevice : public Device { public: - I2CDevice() : Device(I2C) { } + I2CDevice() : Device(BUS_TYPE_I2C) { } virtual ~I2CDevice() { } diff --git a/libraries/AP_HAL/SPIDevice.h b/libraries/AP_HAL/SPIDevice.h index 917a5c5388..797ff03ccf 100644 --- a/libraries/AP_HAL/SPIDevice.h +++ b/libraries/AP_HAL/SPIDevice.h @@ -27,7 +27,7 @@ namespace AP_HAL { class SPIDevice : public Device { public: - SPIDevice() : Device(SPI) { } + SPIDevice() : Device(BUS_TYPE_SPI) { } virtual ~SPIDevice() { } /* Device implementation */ diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp index 87821da02d..3af669917e 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp @@ -297,7 +297,7 @@ void AP_InertialSensor_MPU6000::_fifo_enable() bool AP_InertialSensor_MPU6000::_has_auxiliary_bus() { - return _dev->bus_type != AP_HAL::Device::I2C; + return _dev->bus_type != AP_HAL::Device::BUS_TYPE_I2C; } void AP_InertialSensor_MPU6000::start() @@ -610,7 +610,7 @@ bool AP_InertialSensor_MPU6000::_hardware_init(void) hal.scheduler->delay(100); /* bus-dependent initialization */ - if (_dev->bus_type == AP_HAL::Device::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); diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp index d3ac71b5f1..5b7095cb22 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp @@ -276,7 +276,7 @@ bool AP_InertialSensor_MPU9250::_init() bool AP_InertialSensor_MPU9250::_has_auxiliary_bus() { - return _dev->bus_type != AP_HAL::Device::I2C; + return _dev->bus_type != AP_HAL::Device::BUS_TYPE_I2C; } void AP_InertialSensor_MPU9250::start() @@ -484,7 +484,7 @@ bool AP_InertialSensor_MPU9250::_hardware_init(void) hal.scheduler->delay(100); /* bus-dependent initialization */ - if (_dev->bus_type == AP_HAL::Device::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);