Browse Source

AP_InertialSensor: fix copying wrong number of bytes

We should copy only the bytes we read, not the maximum number.
master
Lucas De Marchi 10 years ago committed by Andrew Tridgell
parent
commit
f3f54157be
  1. 2
      libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp

2
libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp

@ -354,7 +354,7 @@ void AP_MPU6000_BusDriver_I2C::read_burst(uint8_t *samples, @@ -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…
Cancel
Save