Browse Source

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

master
Robert Lefebvre 12 years ago committed by Andrew Tridgell
parent
commit
9605bd8ee1
  1. 4
      ArduCopter/config.h

4
ArduCopter/config.h

@ -103,6 +103,7 @@ @@ -103,6 +103,7 @@
# define HELI_YAW_FF 0
# define RC_FAST_SPEED 125
# define STABILIZE_THROTTLE THROTTLE_MANUAL
# define MPU6K_FILTER 10
#endif
@ -118,6 +119,9 @@ @@ -118,6 +119,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.

Loading…
Cancel
Save