HAL_Linux: implement set_split_transfers() API for I2C

This commit is contained in:
Andrew Tridgell 2016-12-09 12:58:34 +11:00 committed by Lucas De Marchi
parent dc26cbc074
commit a2e445cf24
2 changed files with 16 additions and 0 deletions

View File

@ -154,6 +154,16 @@ I2CDevice::~I2CDevice()
bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len,
uint8_t *recv, uint32_t recv_len)
{
if (send_len > 0 && recv_len > 0 && _split_transfers) {
/*
optionally split all I2C transfers. This is needed for some
devices (such as LidarLite) that require that STOP only
happen with SCL high
*/
return transfer(send, send_len, nullptr, 0) &&
transfer(nullptr, 0, recv, recv_len);
}
struct i2c_msg msgs[2] = { };
unsigned nmsgs = 0;

View File

@ -71,10 +71,16 @@ public:
bool adjust_periodic_callback(
AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override;
/* set split transfers flag */
void set_split_transfers(bool set) override {
_split_transfers = set;
}
protected:
I2CBus &_bus;
uint8_t _address;
uint8_t _retries = 0;
bool _split_transfers = false;
};
class I2CDeviceManager : public AP_HAL::I2CDeviceManager {