Global: rename enum SPIDevice to SPIDeviceType

Free the SPIDevice name so to have a consistent name for I2C/SPI device
classes.
This commit is contained in:
Lucas De Marchi 2015-12-07 14:19:26 -02:00
parent eb68f039d7
commit 9d5fb97819
11 changed files with 19 additions and 19 deletions

View File

@ -50,7 +50,7 @@ extern const AP_HAL::HAL& hal;
// SPI Device //////////////////////////////////////////////////////////////////
AP_SerialBus_SPI::AP_SerialBus_SPI(enum AP_HAL::SPIDevice device, enum AP_HAL::SPIDeviceDriver::bus_speed speed) :
AP_SerialBus_SPI::AP_SerialBus_SPI(enum AP_HAL::SPIDeviceType device, enum AP_HAL::SPIDeviceDriver::bus_speed speed) :
_device(device),
_speed(speed),
_spi(NULL),

View File

@ -35,7 +35,7 @@ public:
class AP_SerialBus_SPI : public AP_SerialBus
{
public:
AP_SerialBus_SPI(enum AP_HAL::SPIDevice device, enum AP_HAL::SPIDeviceDriver::bus_speed speed);
AP_SerialBus_SPI(enum AP_HAL::SPIDeviceType device, enum AP_HAL::SPIDeviceDriver::bus_speed speed);
void init();
uint16_t read_16bits(uint8_t reg);
uint32_t read_24bits(uint8_t reg);
@ -46,7 +46,7 @@ public:
void sem_give();
private:
enum AP_HAL::SPIDevice _device;
enum AP_HAL::SPIDeviceType _device;
enum AP_HAL::SPIDeviceDriver::bus_speed _speed;
AP_HAL::SPIDeviceDriver *_spi;
AP_HAL::Semaphore *_spi_sem;

View File

@ -47,7 +47,7 @@ namespace AP_HAL {
* Global names for all of the existing SPI devices on all platforms.
*/
enum SPIDevice {
enum SPIDeviceType {
SPIDevice_Dataflash = 0,
SPIDevice_ADS7844 = 1,
SPIDevice_MS5611 = 2,

View File

@ -8,7 +8,7 @@
class AP_HAL::SPIDeviceManager {
public:
virtual void init() = 0;
virtual AP_HAL::SPIDeviceDriver* device(enum AP_HAL::SPIDevice, uint8_t index = 0) = 0;
virtual AP_HAL::SPIDeviceDriver* device(enum AP_HAL::SPIDeviceType, uint8_t index = 0) = 0;
};
/**

View File

@ -41,7 +41,7 @@ SPIDeviceManager::SPIDeviceManager()
void SPIDeviceManager::init()
{}
AP_HAL::SPIDeviceDriver* SPIDeviceManager::device(enum AP_HAL::SPIDevice, uint8_t index)
AP_HAL::SPIDeviceDriver* SPIDeviceManager::device(enum AP_HAL::SPIDeviceType, uint8_t index)
{
return &_device;
}

View File

@ -24,7 +24,7 @@ class Empty::SPIDeviceManager : public AP_HAL::SPIDeviceManager {
public:
SPIDeviceManager();
void init();
AP_HAL::SPIDeviceDriver* device(enum AP_HAL::SPIDevice, uint8_t index);
AP_HAL::SPIDeviceDriver* device(enum AP_HAL::SPIDeviceType, uint8_t index);
private:
SPIDeviceDriver _device;
};

View File

@ -93,7 +93,7 @@ void FLYMAPLESPIDeviceManager::init()
{
}
AP_HAL::SPIDeviceDriver* FLYMAPLESPIDeviceManager::device(enum AP_HAL::SPIDevice, uint8_t index)
AP_HAL::SPIDeviceDriver* FLYMAPLESPIDeviceManager::device(enum AP_HAL::SPIDeviceType, uint8_t index)
{
_device.init(); // Defer this until GPIO pin 13 is set up else its a slave
return &_device;

View File

@ -43,7 +43,7 @@ class AP_HAL_FLYMAPLE_NS::FLYMAPLESPIDeviceManager : public AP_HAL::SPIDeviceMan
public:
FLYMAPLESPIDeviceManager();
void init();
AP_HAL::SPIDeviceDriver* device(enum AP_HAL::SPIDevice, uint8_t index);
AP_HAL::SPIDeviceDriver* device(enum AP_HAL::SPIDeviceType, uint8_t index);
private:
FLYMAPLESPIDeviceDriver _device;
};

View File

@ -82,7 +82,7 @@ SPIDeviceDriver SPIDeviceManager::_device[0];
// have a separate semaphore per bus
Semaphore SPIDeviceManager::_semaphore[LINUX_SPI_MAX_BUSES];
SPIDeviceDriver::SPIDeviceDriver(uint16_t bus, uint16_t subdev, enum AP_HAL::SPIDevice type, uint8_t mode, uint8_t bitsPerWord, int16_t cs_pin, uint32_t lowspeed, uint32_t highspeed):
SPIDeviceDriver::SPIDeviceDriver(uint16_t bus, uint16_t subdev, enum AP_HAL::SPIDeviceType type, uint8_t mode, uint8_t bitsPerWord, int16_t cs_pin, uint32_t lowspeed, uint32_t highspeed):
_bus(bus),
_subdev(subdev),
_type(type),
@ -174,7 +174,7 @@ void SPIDeviceManager::init()
}
}
void SPIDeviceManager::cs_assert(enum AP_HAL::SPIDevice type)
void SPIDeviceManager::cs_assert(enum AP_HAL::SPIDeviceType type)
{
uint16_t bus = 0, i;
for (i=0; i<LINUX_SPI_DEVICE_NUM_DEVICES; i++) {
@ -210,7 +210,7 @@ void SPIDeviceManager::cs_assert(enum AP_HAL::SPIDevice type)
}
}
void SPIDeviceManager::cs_release(enum AP_HAL::SPIDevice type)
void SPIDeviceManager::cs_release(enum AP_HAL::SPIDeviceType type)
{
uint16_t bus = 0, i;
for (i=0; i<LINUX_SPI_DEVICE_NUM_DEVICES; i++) {
@ -277,7 +277,7 @@ bool SPIDeviceManager::transaction(SPIDeviceDriver &driver, const uint8_t *tx, u
/*
return a SPIDeviceDriver for a particular device
*/
AP_HAL::SPIDeviceDriver *SPIDeviceManager::device(enum AP_HAL::SPIDevice dev, uint8_t index)
AP_HAL::SPIDeviceDriver *SPIDeviceManager::device(enum AP_HAL::SPIDeviceType dev, uint8_t index)
{
uint8_t count = 0;
for (uint8_t i=0; i<LINUX_SPI_DEVICE_NUM_DEVICES; i++) {

View File

@ -18,7 +18,7 @@
class Linux::SPIDeviceDriver : public AP_HAL::SPIDeviceDriver {
public:
friend class Linux::SPIDeviceManager;
SPIDeviceDriver(uint16_t bus, uint16_t subdev, enum AP_HAL::SPIDevice type, uint8_t mode, uint8_t bitsPerWord, int16_t cs_pin, uint32_t lowspeed, uint32_t highspeed);
SPIDeviceDriver(uint16_t bus, uint16_t subdev, enum AP_HAL::SPIDeviceType type, uint8_t mode, uint8_t bitsPerWord, int16_t cs_pin, uint32_t lowspeed, uint32_t highspeed);
void init();
AP_HAL::Semaphore *get_semaphore();
bool transaction(const uint8_t *tx, uint8_t *rx, uint16_t len);
@ -39,19 +39,19 @@ private:
uint32_t _lowspeed;
uint32_t _highspeed;
uint32_t _speed;
enum AP_HAL::SPIDevice _type;
enum AP_HAL::SPIDeviceType _type;
int _fd; // Per-device FD.
};
class Linux::SPIDeviceManager : public AP_HAL::SPIDeviceManager {
public:
void init();
AP_HAL::SPIDeviceDriver* device(enum AP_HAL::SPIDevice, uint8_t index = 0);
AP_HAL::SPIDeviceDriver* device(enum AP_HAL::SPIDeviceType, uint8_t index = 0);
static AP_HAL::Semaphore *get_semaphore(uint16_t bus);
static void cs_assert(enum AP_HAL::SPIDevice type);
static void cs_release(enum AP_HAL::SPIDevice type);
static void cs_assert(enum AP_HAL::SPIDeviceType type);
static void cs_release(enum AP_HAL::SPIDeviceType type);
static bool transaction(SPIDeviceDriver &driver, const uint8_t *tx, uint8_t *rx, uint16_t len);
private:

View File

@ -16,7 +16,7 @@ void setup(void)
static struct {
const char *name;
enum AP_HAL::SPIDevice dev;
enum AP_HAL::SPIDeviceType dev;
uint8_t whoami_reg;
} whoami_list[] = {
{ "MS5611", AP_HAL::SPIDevice_MS5611, 0x00 | 0x80 },