diff --git a/ArduCopterMega/Attitude.pde b/ArduCopterMega/Attitude.pde index 3704173f2e..ed03bda315 100644 --- a/ArduCopterMega/Attitude.pde +++ b/ArduCopterMega/Attitude.pde @@ -241,13 +241,14 @@ output_yaw_with_hold(boolean hold) yaw_error = wrap_180(yaw_error); // limit the error we're feeding to the PID - yaw_error = constrain(yaw_error, -4000, 4000); // limit error to 60 degees + yaw_error = constrain(yaw_error, -4000, 4000); // limit error to 40 degees // Apply PID and save the new angle back to RC_Channel g.rc_4.servo_out = g.pid_yaw.get_pi(yaw_error, delta_ms_fast_loop, 1.0); // .4 * 4000 = 1600 // add in yaw dampener - g.rc_4.servo_out -= constrain(dampener, -1600, 1600); + g.rc_4.servo_out -= dampener; + yaw_debug = YAW_HOLD; //0 }else{ @@ -265,6 +266,7 @@ output_yaw_with_hold(boolean hold) long error = ((long)g.rc_4.control_in * 6) - (rate * 2); // control is += 6000 * 6 = 36000 g.rc_4.servo_out = g.pid_acro_rate_yaw.get_pid(error, delta_ms_fast_loop, 1.0); // kP .07 * 36000 = 2520 yaw_debug = YAW_RATE; // 2 + nav_yaw = dcm.yaw_sensor; // } } diff --git a/ArduCopterMega/Log.pde b/ArduCopterMega/Log.pde index 0169f05e61..8136e5572b 100644 --- a/ArduCopterMega/Log.pde +++ b/ArduCopterMega/Log.pde @@ -489,7 +489,7 @@ void Log_Write_Control_Tuning() DataFlash.WriteByte(yaw_debug); DataFlash.WriteInt((int)(dcm.yaw_sensor/100)); DataFlash.WriteInt((int)(nav_yaw/100)); - DataFlash.WriteInt((int)yaw_error); + DataFlash.WriteInt((int)yaw_error/100); DataFlash.WriteInt((int)(omega.z * 1000)); // Alt hold diff --git a/ArduCopterMega/config.h b/ArduCopterMega/config.h index a3ab05800d..26fa457abd 100644 --- a/ArduCopterMega/config.h +++ b/ArduCopterMega/config.h @@ -354,13 +354,13 @@ // 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.6 // increase for more aggressive Yaw Hold, decrease if it's bouncy #endif #ifndef YAW_I # define YAW_I 0.01 // set to .0001 to try and get over user's steady state error caused by poor balance #endif #ifndef YAW_D -# define YAW_D 0.05 // Trying a lower value to prevent odd behavior +# define YAW_D 0.1 // Trying a lower value to prevent odd behavior #endif #ifndef YAW_IMAX # define YAW_IMAX 1 // degrees * 100 diff --git a/ArduCopterMega/system.pde b/ArduCopterMega/system.pde index 1a02f6dbb3..b6316ac311 100644 --- a/ArduCopterMega/system.pde +++ b/ArduCopterMega/system.pde @@ -37,7 +37,7 @@ const struct Menu::command main_menu_commands[] PROGMEM = { }; // Create the top-level menu object. -MENU(main_menu, "AC 2.0.16 Beta", main_menu_commands); +MENU(main_menu, "AC 2.0.17 Beta", main_menu_commands); void init_ardupilot() {