mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
trying to improve Yaw issues. Enabled I term for yaw. This was mistakenly Imaxed to 0
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2359 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
e334332682
commit
9241691b44
@ -212,12 +212,11 @@ output_yaw_with_hold(boolean hold)
|
||||
// look to see if we have exited rate control properly - ie stopped turning
|
||||
if(rate_yaw_flag){
|
||||
// we are still in motion from rate control
|
||||
if(fabs(omega.z) < .2){
|
||||
if(fabs(omega.z) < .4){
|
||||
clear_yaw_control();
|
||||
hold = true; // just to be explicit
|
||||
//Serial.print("C");
|
||||
}else{
|
||||
|
||||
hold = false; // return to rate control until we slow down.
|
||||
//Serial.print("D");
|
||||
}
|
||||
|
@ -347,16 +347,16 @@
|
||||
// YAW Control
|
||||
//
|
||||
#ifndef YAW_P
|
||||
# define YAW_P 0.4 // increase for more aggressive Yaw Hold, decrease if it's bouncy
|
||||
# define YAW_P 0.4 // increase for more aggressive Yaw Hold, decrease if it's bouncy
|
||||
#endif
|
||||
#ifndef YAW_I
|
||||
# define YAW_I 0.1 // increased to .1 to try and get over user's steady state error caused by poor balance
|
||||
# define YAW_I 0.01 // increased to .1 to try and get over user's steady state error caused by poor balance
|
||||
#endif
|
||||
#ifndef YAW_D
|
||||
# define YAW_D 0.13 // Trying a lower value to prevent odd behavior
|
||||
#endif
|
||||
#ifndef YAW_IMAX
|
||||
# define YAW_IMAX 0 // Always 0
|
||||
# define YAW_IMAX 500 // Always 0
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
Loading…
Reference in New Issue
Block a user