mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
ArduCopter: reduce Stabilize Yaw P term to 4.5
This commit is contained in:
parent
e375a27058
commit
af1d6a9b82
@ -682,7 +682,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef STABILIZE_YAW_P
|
||||
# define STABILIZE_YAW_P 7.0 // increase for more aggressive Yaw Hold, decrease if it's bouncy
|
||||
# define STABILIZE_YAW_P 4.5 // increase for more aggressive Yaw Hold, decrease if it's bouncy
|
||||
#endif
|
||||
#ifndef STABILIZE_YAW_I
|
||||
# define STABILIZE_YAW_I 0.02
|
||||
|
Loading…
Reference in New Issue
Block a user