AP_HAL_Linux: I2CDevice: use read flag in read_registers_multiple

Use the generic support in Device interface for read flag when we are
using read_registers_multiple() method.
This commit is contained in:
Gustavo Jose de Sousa 2016-06-06 17:37:25 -03:00 committed by Lucas De Marchi
parent 66f1ad9ed0
commit d35cf60ce1

View File

@ -166,6 +166,8 @@ bool I2CDevice::read_registers_multiple(uint8_t first_reg, uint8_t *recv,
{
const uint8_t max_times = I2C_RDRW_IOCTL_MAX_MSGS / 2;
first_reg |= _read_flag;
while (times > 0) {
uint8_t n = MIN(times, max_times);
struct i2c_msg msgs[2 * n];