AP_HAL: AP_HAL_Linux: perfect I2CDevice::transfer()
According to man 3 ioctl, ioctl returns other values than -1 on success. So loop while ioctl returns -1. Furthermore, there is no necessity to initialise r with -EINVAL, Signed-off-by: Ralf Ramsauer <ralf.ramsauer@othr.de>
This commit is contained in:
parent
9eca21c26a
commit
25c7e8bf60
@ -177,13 +177,13 @@ bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len,
|
||||
i2c_data.msgs = msgs;
|
||||
i2c_data.nmsgs = nmsgs;
|
||||
|
||||
int r = -EINVAL;
|
||||
int r;
|
||||
unsigned retries = _retries;
|
||||
do {
|
||||
r = ::ioctl(_bus.fd, I2C_RDWR, &i2c_data);
|
||||
} while (r < 0 && retries-- > 0);
|
||||
} while (r == -1 && retries-- > 0);
|
||||
|
||||
return r >= 0;
|
||||
return r != -1;
|
||||
}
|
||||
|
||||
bool I2CDevice::read_registers_multiple(uint8_t first_reg, uint8_t *recv,
|
||||
|
Loading…
Reference in New Issue
Block a user