AP_InertialSensor: MPU9250: publish gyro raw sample rate
So that delta angle calculation is enabled.
This commit is contained in:
parent
887f81274d
commit
be8070e335
@ -316,6 +316,7 @@ bool AP_InertialSensor_MPU9250::_init_sensor(AP_HAL::SPIDeviceDriver *spi)
|
||||
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_InertialSensor_MPU9250::_poll_data, void));
|
||||
|
||||
_set_accel_raw_sample_rate(_accel_instance, DEFAULT_SAMPLE_RATE);
|
||||
_set_gyro_raw_sample_rate(_gyro_instance, DEFAULT_SAMPLE_RATE);
|
||||
|
||||
#if MPU9250_DEBUG
|
||||
_dump_registers(_spi);
|
||||
|
Loading…
Reference in New Issue
Block a user