mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: tidy up MPU6000 driver
This commit is contained in:
parent
2d47a07480
commit
3ce7667e5a
|
@ -507,10 +507,11 @@ bool AP_InertialSensor_MPU6000::_hardware_init(AP_InertialSensor::Sample_rate sa
|
||||||
_sample_count = 2;
|
_sample_count = 2;
|
||||||
break;
|
break;
|
||||||
case AP_InertialSensor::RATE_200HZ:
|
case AP_InertialSensor::RATE_200HZ:
|
||||||
default:
|
|
||||||
default_filter = BITS_DLPF_CFG_20HZ;
|
default_filter = BITS_DLPF_CFG_20HZ;
|
||||||
_sample_count = 1;
|
_sample_count = 1;
|
||||||
break;
|
break;
|
||||||
|
default:
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
_set_filter_register(_imu.get_filter(), default_filter);
|
_set_filter_register(_imu.get_filter(), default_filter);
|
||||||
|
|
Loading…
Reference in New Issue