mirror of https://github.com/ArduPilot/ardupilot
TradHeli: disable AutoTune for Tradheli compile
We need the flash space, and this probably won't work for tradheli anyway since tradheli needs most of the control from Feedforward rather than P term. And D-term is very very bad.
This commit is contained in:
parent
1db3c6e688
commit
531a9f4f25
|
@ -103,25 +103,28 @@
|
|||
/////////////////////////////////////////////////////////////////////////////////
|
||||
// TradHeli defaults
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
# define RC_FAST_SPEED 125
|
||||
# define WP_YAW_BEHAVIOR_DEFAULT WP_YAW_BEHAVIOR_LOOK_AHEAD
|
||||
# define RATE_INTEGRATOR_LEAK_RATE 0.02f
|
||||
# define RATE_ROLL_D 0
|
||||
# define RATE_PITCH_D 0
|
||||
# define HELI_PITCH_FF 0
|
||||
# define HELI_ROLL_FF 0
|
||||
# define HELI_YAW_FF 0
|
||||
# define STABILIZE_THR THROTTLE_MANUAL_HELI
|
||||
# define MPU6K_FILTER 10
|
||||
# define HELI_STAB_COLLECTIVE_MIN_DEFAULT 0
|
||||
# define HELI_STAB_COLLECTIVE_MAX_DEFAULT 1000
|
||||
# define THR_MIN_DEFAULT 0
|
||||
# define RC_FAST_SPEED 125
|
||||
# define WP_YAW_BEHAVIOR_DEFAULT WP_YAW_BEHAVIOR_LOOK_AHEAD
|
||||
# define RATE_INTEGRATOR_LEAK_RATE 0.02f
|
||||
# define RATE_ROLL_D 0
|
||||
# define RATE_PITCH_D 0
|
||||
# define HELI_PITCH_FF 0
|
||||
# define HELI_ROLL_FF 0
|
||||
# define HELI_YAW_FF 0
|
||||
# define STABILIZE_THR THROTTLE_MANUAL_HELI
|
||||
# define MPU6K_FILTER 10
|
||||
# define HELI_STAB_COLLECTIVE_MIN_DEFAULT 0
|
||||
# define HELI_STAB_COLLECTIVE_MAX_DEFAULT 1000
|
||||
# define THR_MIN_DEFAULT 0
|
||||
# define AUTOTUNE DISABLED
|
||||
|
||||
# ifndef HELI_CC_COMP
|
||||
#define HELI_CC_COMP DISABLED
|
||||
#endif
|
||||
# ifndef HELI_PIRO_COMP
|
||||
#define HELI_PIRO_COMP DISABLED
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
/////////////////////////////////////////////////////////////////////////////////
|
||||
|
|
Loading…
Reference in New Issue