Revert "AP_HAL_PX4: embed PX4_I2C object into I2CDevice"

This reverts commit 54fd3702c3.

These commits broke startup on PX4
This commit is contained in:
Andrew Tridgell 2016-05-11 12:14:27 +10:00
parent bcc64e0b4a
commit 8c06e6cddc
2 changed files with 24 additions and 25 deletions

View File

@ -4,29 +4,26 @@
namespace PX4 { namespace PX4 {
I2CDevice::PX4_I2C::PX4_I2C(uint8_t bus) class PX4_I2C : public device::I2C {
: I2C("AP_I2C", "/dev/api2c", bus, 0, 400000UL) public:
PX4_I2C(uint8_t bus);
bool do_transfer(uint8_t address, const uint8_t *send, uint32_t send_len,
uint8_t *recv, uint32_t recv_len);
};
PX4_I2C::PX4_I2C(uint8_t bus) :
I2C("AP_I2C", "/dev/api2c", bus, 0, 400000UL)
{ {
init(); init();
} }
bool I2CDevice::PX4_I2C::do_transfer(uint8_t address, const uint8_t *send, uint32_t send_len, bool PX4_I2C::do_transfer(uint8_t address, const uint8_t *send, uint32_t send_len,
uint8_t *recv, uint32_t recv_len) uint8_t *recv, uint32_t recv_len)
{ {
set_address(address); set_address(address);
return transfer(send, send_len, recv, recv_len) == OK; return transfer(send, send_len, recv, recv_len) == OK;
} }
I2CDevice::I2CDevice(uint8_t bus, uint8_t address)
: _device(bus)
, _address(address)
{
}
I2CDevice::~I2CDevice()
{
}
bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len, bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len,
uint8_t *recv, uint32_t recv_len) uint8_t *recv, uint32_t recv_len)
{ {
@ -57,6 +54,10 @@ AP_HAL::Semaphore *I2CDevice::get_semaphore()
return &semaphore; return &semaphore;
} }
I2CDevice::~I2CDevice()
{
}
I2CDeviceManager::I2CDeviceManager() I2CDeviceManager::I2CDeviceManager()
{ {
} }
@ -64,8 +65,9 @@ I2CDeviceManager::I2CDeviceManager()
AP_HAL::OwnPtr<AP_HAL::I2CDevice> AP_HAL::OwnPtr<AP_HAL::I2CDevice>
I2CDeviceManager::get_device(uint8_t bus, uint8_t address) I2CDeviceManager::get_device(uint8_t bus, uint8_t address)
{ {
auto dev = AP_HAL::OwnPtr<AP_HAL::I2CDevice>(new I2CDevice(bus, address)); AP_HAL::OwnPtr<PX4_I2C> i2c { new PX4_I2C(bus) };
auto dev = AP_HAL::OwnPtr<AP_HAL::I2CDevice>(new I2CDevice(*i2c, address));
return dev; return dev;
} }
} }

View File

@ -21,7 +21,11 @@ public:
} }
/* AP_HAL::I2CDevice implementation */ /* AP_HAL::I2CDevice implementation */
I2CDevice(uint8_t bus, uint8_t address); I2CDevice(PX4_I2C &device, uint8_t address)
: _device(device)
, _address(address)
{
}
~I2CDevice(); ~I2CDevice();
@ -57,14 +61,7 @@ public:
int get_fd() override; int get_fd() override;
protected: protected:
class PX4_I2C : public device::I2C { PX4_I2C &_device;
public:
PX4_I2C(uint8_t bus);
bool do_transfer(uint8_t address, const uint8_t *send, uint32_t send_len,
uint8_t *recv, uint32_t recv_len);
};
PX4_I2C _device;
uint8_t _address; uint8_t _address;
uint8_t _retries = 0; uint8_t _retries = 0;