mirror of https://github.com/ArduPilot/ardupilot
AP_OpticalFlow: The first value of the register to the value of the definition.
This commit is contained in:
parent
5d7ca3fd27
commit
59796aaf9c
|
@ -91,14 +91,14 @@ bool AP_OpticalFlow_Linux::read(optical_flow_s* report)
|
|||
|
||||
// Perform the writing and reading in a single command
|
||||
if (PX4FLOW_REG == 0x00) {
|
||||
if (!_dev->read_registers(0, val, I2C_FRAME_SIZE + I2C_INTEGRAL_FRAME_SIZE)) {
|
||||
if (!_dev->read_registers(PX4FLOW_REG, val, I2C_FRAME_SIZE + I2C_INTEGRAL_FRAME_SIZE)) {
|
||||
goto fail_transfer;
|
||||
}
|
||||
memcpy(&f_integral, &(val[I2C_FRAME_SIZE]), I2C_INTEGRAL_FRAME_SIZE);
|
||||
}
|
||||
|
||||
if (PX4FLOW_REG == 0x16) {
|
||||
if (!_dev->read_registers(0, val, I2C_INTEGRAL_FRAME_SIZE)) {
|
||||
if (!_dev->read_registers(PX4FLOW_REG, val, I2C_INTEGRAL_FRAME_SIZE)) {
|
||||
goto fail_transfer;
|
||||
}
|
||||
memcpy(&f_integral, val, I2C_INTEGRAL_FRAME_SIZE);
|
||||
|
|
Loading…
Reference in New Issue