mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Copter: INS_MPU6K_FILTER defaulted to 20hz
This commit is contained in:
parent
ede3a52eec
commit
4ca58f240c
@ -393,7 +393,7 @@ void AP_InertialSensor_MPU6000::hardware_init(Sample_rate sample_rate)
|
|||||||
break;
|
break;
|
||||||
case RATE_100HZ:
|
case RATE_100HZ:
|
||||||
rate = MPUREG_SMPLRT_100HZ;
|
rate = MPUREG_SMPLRT_100HZ;
|
||||||
default_filter = BITS_DLPF_CFG_42HZ;
|
default_filter = BITS_DLPF_CFG_20HZ;
|
||||||
_micros_per_sample = 10000;
|
_micros_per_sample = 10000;
|
||||||
break;
|
break;
|
||||||
case RATE_200HZ:
|
case RATE_200HZ:
|
||||||
|
Loading…
Reference in New Issue
Block a user