Lowered Yaw to prevent overshoot based on feedback
This commit is contained in:
parent
ea832c0818
commit
74b203c7f2
@ -582,7 +582,7 @@
|
||||
// YAW Control
|
||||
//
|
||||
#ifndef STABILIZE_YAW_P
|
||||
# define STABILIZE_YAW_P 9.5 // increase for more aggressive Yaw Hold, decrease if it's bouncy
|
||||
# define STABILIZE_YAW_P 7.5 // increase for more aggressive Yaw Hold, decrease if it's bouncy
|
||||
#endif
|
||||
#ifndef STABILIZE_YAW_I
|
||||
# define STABILIZE_YAW_I 0.01 // set to .0001 to try and get over user's steady state error caused by poor balance
|
||||
|
Loading…
Reference in New Issue
Block a user