Browse Source

AP_InertialSensor: MPU6000: publish gyro raw sample rate

So that delta angle calculation is enabled.
mission-4.1.18
Gustavo Jose de Sousa 10 years ago committed by Andrew Tridgell
parent
commit
887f81274d
  1. 1
      libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp

1
libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp

@ -594,6 +594,7 @@ void AP_InertialSensor_MPU6000::start() @@ -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();

Loading…
Cancel
Save