From e2edad8a3fd0ec9c047de8b487be8c59cbcf7a0f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 23 Dec 2012 08:59:35 +1100 Subject: [PATCH] InertialSensor: fixed last sample time in MPU6000 we lost this in the final work on the DTR bug --- libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp index 8fa1d8a881..e4e814dc26 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp @@ -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 // interrupt context, called from the main loop. This avoids // all possible conflicts with the DataFlash SPI bus + _last_sample_time_micros = hal.scheduler->micros(); read_data(); } return _count;