mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_InertialSensor: fix copying wrong number of bytes
We should copy only the bytes we read, not the maximum number.
This commit is contained in:
parent
5b2ff84c06
commit
1c3728a585
@ -354,7 +354,7 @@ void AP_MPU6000_BusDriver_I2C::read_burst(uint8_t *samples,
|
||||
return;
|
||||
}
|
||||
|
||||
memcpy(samples, _rx, MPU6000_SAMPLE_SIZE * MPU6000_MAX_FIFO_SAMPLES);
|
||||
memcpy(samples, _rx, n_samples * MPU6000_SAMPLE_SIZE);
|
||||
|
||||
return;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user