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:
Lucas De Marchi 2015-07-28 11:21:16 -03:00 committed by Andrew Tridgell
parent 209e1924a5
commit f3f54157be
1 changed files with 1 additions and 1 deletions

View File

@ -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;
}