From 66d3587b625e596f401c08d6a29d52353c1e7845 Mon Sep 17 00:00:00 2001 From: jasonshort Date: Fri, 15 Apr 2011 05:08:13 +0000 Subject: [PATCH] disabled dampening on yaw for now. will fix tomorrow. git-svn-id: https://arducopter.googlecode.com/svn/trunk@1880 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- ArduCopterMega/Attitude.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopterMega/Attitude.pde b/ArduCopterMega/Attitude.pde index 674f906eef..7de2de1556 100644 --- a/ArduCopterMega/Attitude.pde +++ b/ArduCopterMega/Attitude.pde @@ -163,7 +163,7 @@ output_yaw_with_hold(boolean hold) int dampener = (float)rate * g.hold_yaw_dampener; // 18000 * .17 = 3000 // Limit dampening to be equal to propotional term for symmetry - g.rc_4.servo_out -= constrain(dampener, -max_yaw_dampener, max_yaw_dampener); // -3000 + //g.rc_4.servo_out -= constrain(dampener, -max_yaw_dampener, max_yaw_dampener); // -3000 // Limit Output g.rc_4.servo_out = constrain(g.rc_4.servo_out, -1800, 1800); // limit to 24°