mirror of https://github.com/ArduPilot/ardupilot
InertialSensor: fixed last sample time in MPU6000
we lost this in the final work on the DTR bug
This commit is contained in:
parent
3fda7bbeac
commit
e2edad8a3f
|
@ -501,6 +501,7 @@ uint16_t AP_InertialSensor_MPU6000::num_samples_available()
|
||||||
// Note that doing it this way means we doing the read out of
|
// Note that doing it this way means we doing the read out of
|
||||||
// interrupt context, called from the main loop. This avoids
|
// interrupt context, called from the main loop. This avoids
|
||||||
// all possible conflicts with the DataFlash SPI bus
|
// all possible conflicts with the DataFlash SPI bus
|
||||||
|
_last_sample_time_micros = hal.scheduler->micros();
|
||||||
read_data();
|
read_data();
|
||||||
}
|
}
|
||||||
return _count;
|
return _count;
|
||||||
|
|
Loading…
Reference in New Issue