Global: remove get_fd() from Device API

This was there for compatibility with I2CDriver and SPIDriver. We don't
use them anymore so we can remove the compat method.
This commit is contained in:
Lucas De Marchi 2016-08-10 18:03:10 -03:00
parent ead01855df
commit e1ab44f4a3
11 changed files with 0 additions and 39 deletions

View File

@ -141,12 +141,6 @@ public:
*/
virtual bool unregister_callback(PeriodicHandle h) { return false; }
/*
* Temporary method to get the fd used by this device: it's here only for
* allowing to convert old drivers to this new interface
*/
virtual int get_fd() = 0;
/**
* Some devices connected on the I2C or SPI bus require a bit to be set on
* the register address in order to perform a read operation. This sets a

View File

@ -66,9 +66,6 @@ public:
/* See Device::adjust_periodic_callback() */
virtual bool adjust_periodic_callback(
Device::PeriodicHandle h, uint32_t period_usec) override = 0;
/* See Device::get_fd() */
virtual int get_fd() override = 0;
};
class I2CDeviceManager {

View File

@ -56,8 +56,6 @@ public:
/* See Device::adjust_periodic_callback() */
virtual bool adjust_periodic_callback(
PeriodicHandle h, uint32_t period_usec) override { return false; }
virtual int get_fd() override = 0;
};
class SPIDeviceManager {

View File

@ -77,9 +77,6 @@ public:
{
return true;
}
/* See AP_HAL::Device::get_fd() */
int get_fd() { return -1; }
};
class I2CDeviceManager : public AP_HAL::I2CDeviceManager {

View File

@ -69,9 +69,6 @@ public:
return nullptr;
}
/* See AP_HAL::Device::get_fd() */
int get_fd() override { return -1; }
private:
Semaphore _semaphore;
};

View File

@ -237,11 +237,6 @@ AP_HAL::Semaphore *I2CDevice::get_semaphore()
return &_bus.sem;
}
int I2CDevice::get_fd()
{
return _bus.fd;
}
AP_HAL::Device::PeriodicHandle I2CDevice::register_periodic_callback(
uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
{

View File

@ -76,9 +76,6 @@ public:
bool adjust_periodic_callback(
AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override;
/* See AP_HAL::Device::get_fd() */
int get_fd() override;
protected:
I2CBus &_bus;
uint8_t _address;

View File

@ -353,11 +353,6 @@ AP_HAL::Semaphore *SPIDevice::get_semaphore()
return &_bus.sem;
}
int SPIDevice::get_fd()
{
return _bus.fd;
}
AP_HAL::Device::PeriodicHandle SPIDevice::register_periodic_callback(
uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
{

View File

@ -58,9 +58,6 @@ public:
bool adjust_periodic_callback(
AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override;
/* See AP_HAL::Device::get_fd() */
int get_fd() override;
protected:
SPIBus &_bus;
SPIDesc &_desc;

View File

@ -69,9 +69,6 @@ public:
return false;
}
// this makes no sense on PX4
int get_fd() override { return -1; }
AP_HAL::Semaphore* get_semaphore() override { return &semaphore; }
private:

View File

@ -69,9 +69,6 @@ public:
return false;
}
// this makes no sense on VRBRAIN
int get_fd() override { return -1; }
AP_HAL::Semaphore* get_semaphore() override { return &semaphore; }
private: