HAL_PX4: implement split transfers for I2C

This commit is contained in:
Andrew Tridgell 2017-04-18 12:28:47 +10:00
parent 29adf300ee
commit 3415dfb46c
3 changed files with 27 additions and 14 deletions

View File

@ -62,7 +62,7 @@ uint8_t PX4_I2C::map_bus_number(uint8_t bus) const
/* /*
implement wrapper for PX4 I2C driver implement wrapper for PX4 I2C driver
*/ */
bool PX4_I2C::do_transfer(uint8_t address, const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) bool PX4_I2C::do_transfer(uint8_t address, const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len, bool split_transfers)
{ {
set_address(address); set_address(address);
if (!init_done) { if (!init_done) {
@ -78,18 +78,26 @@ bool PX4_I2C::do_transfer(uint8_t address, const uint8_t *send, uint32_t send_le
if (!init_ok) { if (!init_ok) {
return false; return false;
} }
/*
splitting the transfer() into two pieces avoids a stop condition if (split_transfers) {
with SCL low which is not supported on some devices (such as /*
LidarLite blue label) splitting the transfer() into two pieces avoids a stop condition
*/ with SCL low which is not supported on some devices (such as
if (send && send_len) { LidarLite blue label)
if (transfer(send, send_len, nullptr, 0) != OK) { */
return false; if (send && send_len) {
if (transfer(send, send_len, nullptr, 0) != OK) {
return false;
}
} }
} if (recv && recv_len) {
if (recv && recv_len) { if (transfer(nullptr, 0, recv, recv_len) != OK) {
if (transfer(nullptr, 0, recv, recv_len) != OK) { return false;
}
}
} else {
// combined transfer
if (transfer(send, send_len, recv, recv_len) != OK) {
return false; return false;
} }
} }
@ -120,7 +128,7 @@ 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)
{ {
perf_begin(perf); perf_begin(perf);
bool ret = _px4dev.do_transfer(_address, send, send_len, recv, recv_len); bool ret = _px4dev.do_transfer(_address, send, send_len, recv, recv_len, _split_transfers);
perf_end(perf); perf_end(perf);
return ret; return ret;
} }

View File

@ -65,6 +65,10 @@ public:
return &businfo[_busnum<num_buses?_busnum:0].semaphore; return &businfo[_busnum<num_buses?_busnum:0].semaphore;
} }
void set_split_transfers(bool set) override {
_split_transfers = set;
}
private: private:
static const uint8_t num_buses = 2; static const uint8_t num_buses = 2;
static DeviceBus businfo[num_buses]; static DeviceBus businfo[num_buses];
@ -74,6 +78,7 @@ private:
uint8_t _address; uint8_t _address;
perf_counter_t perf; perf_counter_t perf;
char *pname; char *pname;
bool _split_transfers;
}; };
class I2CDeviceManager : public AP_HAL::I2CDeviceManager { class I2CDeviceManager : public AP_HAL::I2CDeviceManager {

View File

@ -14,7 +14,7 @@ extern const AP_HAL::HAL& hal;
class PX4::PX4_I2C : public device::I2C { class PX4::PX4_I2C : public device::I2C {
public: public:
PX4_I2C(uint8_t bus); 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); bool do_transfer(uint8_t address, const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len, bool split_transfers);
void set_retries(uint8_t retries) { void set_retries(uint8_t retries) {
_retries = retries; _retries = retries;