Browse Source

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.
master
Gustavo Jose de Sousa 9 years ago committed by Lucas De Marchi
parent
commit
d35cf60ce1
  1. 2
      libraries/AP_HAL_Linux/I2CDevice.cpp

2
libraries/AP_HAL_Linux/I2CDevice.cpp

@ -166,6 +166,8 @@ bool I2CDevice::read_registers_multiple(uint8_t first_reg, uint8_t *recv, @@ -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];

Loading…
Cancel
Save