INS: updated MPU6K_FILTER parameter description

This commit is contained in:
Randy Mackay 2013-04-10 00:14:53 +09:00
parent 217b8d7a59
commit 86fe79a662

View File

@ -83,7 +83,7 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] PROGMEM = {
// @Param: MPU6K_FILTER
// @DisplayName: MPU6000 filter frequency
// @Description: Filter frequency to ask the MPU6000 to apply to samples. This can be set to a lower value to try to cope with very high vibration levels in aircraft. The default value on ArduPlane and APMrover2 is 20Hz. The default value on ArduCopter is 42Hz. This option takes effect on the next reboot or gyro initialisation
// @Description: Filter frequency to ask the MPU6000 to apply to samples. This can be set to a lower value to try to cope with very high vibration levels in aircraft. The default value on ArduPlane, APMrover2 and ArduCopter is 20Hz. This option takes effect on the next reboot or gyro initialisation
// @Units: Hz
// @Values: 0:Default,5:5Hz,10:10Hz,20:20Hz,42:42Hz,98:98Hz
// @User: Advanced