mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
ACM: Trying to set a default MPU6K filter rate of 10Hz for TradHeli. Doesn't Work.
This commit is contained in:
parent
d926360e81
commit
9605bd8ee1
@ -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 @@
|
||||
#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…
Reference in New Issue
Block a user