HAL_Linux: implement set_split_transfers() API for I2C
This commit is contained in:
parent
dc26cbc074
commit
a2e445cf24
@ -154,6 +154,16 @@ 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)
|
||||||
{
|
{
|
||||||
|
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] = { };
|
struct i2c_msg msgs[2] = { };
|
||||||
unsigned nmsgs = 0;
|
unsigned nmsgs = 0;
|
||||||
|
|
||||||
|
@ -71,10 +71,16 @@ public:
|
|||||||
bool adjust_periodic_callback(
|
bool adjust_periodic_callback(
|
||||||
AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override;
|
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:
|
protected:
|
||||||
I2CBus &_bus;
|
I2CBus &_bus;
|
||||||
uint8_t _address;
|
uint8_t _address;
|
||||||
uint8_t _retries = 0;
|
uint8_t _retries = 0;
|
||||||
|
bool _split_transfers = false;
|
||||||
};
|
};
|
||||||
|
|
||||||
class I2CDeviceManager : public AP_HAL::I2CDeviceManager {
|
class I2CDeviceManager : public AP_HAL::I2CDeviceManager {
|
||||||
|
Loading…
Reference in New Issue
Block a user