mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-27 10:13:57 -04:00
AP_HAL_Linux: move check for _split_transfers
This is likely not true, so allow not to check the other conditions. Also remove comment since this is going to be added to the method.
This commit is contained in:
parent
df1da3c14e
commit
32d208dbe8
@ -154,16 +154,11 @@ 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
|
||||
*/
|
||||
if (_split_transfers && send_len > 0 && recv_len > 0) {
|
||||
return transfer(send, send_len, nullptr, 0) &&
|
||||
transfer(nullptr, 0, recv, recv_len);
|
||||
}
|
||||
|
||||
|
||||
struct i2c_msg msgs[2] = { };
|
||||
unsigned nmsgs = 0;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user