disabled dampening on yaw for now. will fix tomorrow.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1880 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-04-15 05:08:13 +00:00
parent 9b96a18ad4
commit 66d3587b62
1 changed files with 1 additions and 1 deletions

View File

@ -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°