mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
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:
parent
66f1ad9ed0
commit
d35cf60ce1
@ -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;
|
const uint8_t max_times = I2C_RDRW_IOCTL_MAX_MSGS / 2;
|
||||||
|
|
||||||
|
first_reg |= _read_flag;
|
||||||
|
|
||||||
while (times > 0) {
|
while (times > 0) {
|
||||||
uint8_t n = MIN(times, max_times);
|
uint8_t n = MIN(times, max_times);
|
||||||
struct i2c_msg msgs[2 * n];
|
struct i2c_msg msgs[2 * n];
|
||||||
|
Loading…
Reference in New Issue
Block a user