mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: Add read method
Provide a more intuitive api for reading an I2CDevice.
This commit is contained in:
parent
08ea1ea263
commit
d5449a6f20
|
@ -90,6 +90,16 @@ public:
|
|||
return transfer(buf, sizeof(buf), nullptr, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Wrapper function over #transfer() to read a sequence of bytes from
|
||||
* device. No value is written, differently from the #read_registers()
|
||||
* method and hence doesn't include the read flag set by #set_read_flag()
|
||||
*/
|
||||
bool read(uint8_t *recv, uint32_t recv_len)
|
||||
{
|
||||
return transfer(nullptr, 0, recv, recv_len);
|
||||
}
|
||||
|
||||
/*
|
||||
* Get the semaphore for the bus this device is in. This is intended for
|
||||
* drivers to use during initialization phase only.
|
||||
|
|
Loading…
Reference in New Issue