mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 09:38:29 -04:00
Copter: Trad Heli-change default accel_z_p to 0.30
prevents collective cycling in altitude controlled modes
This commit is contained in:
parent
93810ab42a
commit
572c609cd6
@ -69,6 +69,7 @@
|
|||||||
# define WP_YAW_BEHAVIOR_DEFAULT WP_YAW_BEHAVIOR_LOOK_AHEAD
|
# define WP_YAW_BEHAVIOR_DEFAULT WP_YAW_BEHAVIOR_LOOK_AHEAD
|
||||||
# define THR_MIN_DEFAULT 0
|
# define THR_MIN_DEFAULT 0
|
||||||
# define AUTOTUNE_ENABLED DISABLED
|
# define AUTOTUNE_ENABLED DISABLED
|
||||||
|
# define ACCEL_Z_P 0.30f
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
Loading…
Reference in New Issue
Block a user