ACM: Trying to set a default MPU6K filter rate of 10Hz for TradHeli. Doesn't Work.

This commit is contained in:
Robert Lefebvre 2012-12-13 14:54:14 -05:00
parent 2656997714
commit b83049bdda
2 changed files with 14 additions and 0 deletions

View File

@ -97,6 +97,7 @@
# define HELI_YAW_FF 0
# define RC_FAST_SPEED 125
# define STABILIZE_THROTTLE THROTTLE_MANUAL
# define MPU6K_FILTER 10
#endif
@ -112,6 +113,9 @@
#ifndef CONFIG_IMU_TYPE
# define CONFIG_IMU_TYPE CONFIG_IMU_OILPAN
#endif
#ifndef MPU6K_FILTER
# define MPU6K_FILTER MPU6K_DEFAULT_FILTER
#endif
//////////////////////////////////////////////////////////////////////////////
// ADC Enable - used to eliminate for systems which don't have ADC.

View File

@ -411,6 +411,16 @@ enum gcs_severity {
#define CONFIG_IMU_OILPAN 1
#define CONFIG_IMU_MPU6000 2
// MPU6K Filter Rates
# define MPU6K_DEFAULT_FILTER 0
# define MPU6K_5HZ_FILTER 5
# define MPU6K_10HZ_FILTER 10
# define MPU6K_20HZ_FILTER 20
# define MPU6K_42HZ_FILTER 42
# define MPU6K_98HZ_FILTER 98
// APM Hardware selection
#define APM_HARDWARE_APM1 1
#define APM_HARDWARE_APM2 2