From 887f81274d46875655a4ab7b35c09c2f55176fa9 Mon Sep 17 00:00:00 2001 From: Gustavo Jose de Sousa Date: Mon, 21 Sep 2015 14:08:50 -0300 Subject: [PATCH] AP_InertialSensor: MPU6000: publish gyro raw sample rate So that delta angle calculation is enabled. --- 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 02e693319b..e423a2ee38 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp @@ -594,6 +594,7 @@ void AP_InertialSensor_MPU6000::start() _accel_instance = _imu.register_accel(); _set_accel_raw_sample_rate(_accel_instance, 1000); + _set_gyro_raw_sample_rate(_gyro_instance, 1000); hal.scheduler->resume_timer_procs();