mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
Global: rename bus type enum entries
This commit is contained in:
parent
f6bebc96c0
commit
1f96336f7c
@ -27,8 +27,8 @@
|
|||||||
class AP_HAL::Device {
|
class AP_HAL::Device {
|
||||||
public:
|
public:
|
||||||
enum BusType {
|
enum BusType {
|
||||||
I2C,
|
BUS_TYPE_I2C,
|
||||||
SPI,
|
BUS_TYPE_SPI,
|
||||||
};
|
};
|
||||||
|
|
||||||
enum Speed {
|
enum Speed {
|
||||||
|
@ -27,7 +27,7 @@ namespace AP_HAL {
|
|||||||
|
|
||||||
class I2CDevice : public Device {
|
class I2CDevice : public Device {
|
||||||
public:
|
public:
|
||||||
I2CDevice() : Device(I2C) { }
|
I2CDevice() : Device(BUS_TYPE_I2C) { }
|
||||||
|
|
||||||
virtual ~I2CDevice() { }
|
virtual ~I2CDevice() { }
|
||||||
|
|
||||||
|
@ -27,7 +27,7 @@ namespace AP_HAL {
|
|||||||
|
|
||||||
class SPIDevice : public Device {
|
class SPIDevice : public Device {
|
||||||
public:
|
public:
|
||||||
SPIDevice() : Device(SPI) { }
|
SPIDevice() : Device(BUS_TYPE_SPI) { }
|
||||||
|
|
||||||
virtual ~SPIDevice() { }
|
virtual ~SPIDevice() { }
|
||||||
/* Device implementation */
|
/* Device implementation */
|
||||||
|
@ -297,7 +297,7 @@ void AP_InertialSensor_MPU6000::_fifo_enable()
|
|||||||
|
|
||||||
bool AP_InertialSensor_MPU6000::_has_auxiliary_bus()
|
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()
|
void AP_InertialSensor_MPU6000::start()
|
||||||
@ -610,7 +610,7 @@ bool AP_InertialSensor_MPU6000::_hardware_init(void)
|
|||||||
hal.scheduler->delay(100);
|
hal.scheduler->delay(100);
|
||||||
|
|
||||||
/* bus-dependent initialization */
|
/* 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
|
/* Disable I2C bus if SPI selected (Recommended in Datasheet to be
|
||||||
* done just after the device is reset) */
|
* done just after the device is reset) */
|
||||||
_register_write(MPUREG_USER_CTRL, BIT_USER_CTRL_I2C_IF_DIS);
|
_register_write(MPUREG_USER_CTRL, BIT_USER_CTRL_I2C_IF_DIS);
|
||||||
|
@ -276,7 +276,7 @@ bool AP_InertialSensor_MPU9250::_init()
|
|||||||
|
|
||||||
bool AP_InertialSensor_MPU9250::_has_auxiliary_bus()
|
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()
|
void AP_InertialSensor_MPU9250::start()
|
||||||
@ -484,7 +484,7 @@ bool AP_InertialSensor_MPU9250::_hardware_init(void)
|
|||||||
hal.scheduler->delay(100);
|
hal.scheduler->delay(100);
|
||||||
|
|
||||||
/* bus-dependent initialization */
|
/* 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
|
/* Disable I2C bus if SPI selected (Recommended in Datasheet to be
|
||||||
* done just after the device is reset) */
|
* done just after the device is reset) */
|
||||||
_register_write(MPUREG_USER_CTRL, BIT_USER_CTRL_I2C_IF_DIS);
|
_register_write(MPUREG_USER_CTRL, BIT_USER_CTRL_I2C_IF_DIS);
|
||||||
|
Loading…
Reference in New Issue
Block a user