mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
AP_InertialSensor: fixed instance usage in set_gyro_oversampling()
thanks Francisco!
This commit is contained in:
parent
112b22516a
commit
519a293af9
@ -813,7 +813,7 @@ void AP_InertialSensor_Invensense::_set_filter_register(void)
|
|||||||
|
|
||||||
// for logging purposes set the oversamping rate
|
// for logging purposes set the oversamping rate
|
||||||
_set_accel_oversampling(_accel_instance, MPU_FIFO_DOWNSAMPLE_COUNT/2);
|
_set_accel_oversampling(_accel_instance, MPU_FIFO_DOWNSAMPLE_COUNT/2);
|
||||||
_set_gyro_oversampling(_accel_instance, MPU_FIFO_DOWNSAMPLE_COUNT);
|
_set_gyro_oversampling(_gyro_instance, MPU_FIFO_DOWNSAMPLE_COUNT);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user