AP_InertialSensor: MPU6000: publish gyro raw sample rate

So that delta angle calculation is enabled.
This commit is contained in:
Gustavo Jose de Sousa 2015-09-21 14:08:50 -03:00 committed by Andrew Tridgell
parent 31a49d318c
commit 887f81274d
1 changed files with 1 additions and 0 deletions

View File

@ -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();