mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: AP_HAL_Linux: align I2CDevice::read_registers_multiple()
25c7e8b
changed the logic of transfer(). Align
I2CDevice::read_registers_multiple() in the same way.
Signed-off-by: Ralf Ramsauer <ralf.ramsauer@othr.de>
This commit is contained in:
parent
cba480d02b
commit
71212942da
|
@ -217,13 +217,13 @@ bool I2CDevice::read_registers_multiple(uint8_t first_reg, uint8_t *recv,
|
||||||
recv += recv_len;
|
recv += recv_len;
|
||||||
};
|
};
|
||||||
|
|
||||||
int r = -EINVAL;
|
int r;
|
||||||
unsigned retries = _retries;
|
unsigned retries = _retries;
|
||||||
do {
|
do {
|
||||||
r = ::ioctl(_bus.fd, I2C_RDWR, &i2c_data);
|
r = ::ioctl(_bus.fd, I2C_RDWR, &i2c_data);
|
||||||
} while (r < 0 && retries-- > 0);
|
} while (r == -1 && retries-- > 0);
|
||||||
|
|
||||||
if (r < 0) {
|
if (r == -1) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue