From 0d8071a4013a162040c38d882d7a01ce13fcef66 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 3 Dec 2011 17:55:11 -0800 Subject: [PATCH] Added new gain and clamp value for DCM --- ArduCopter/system.pde | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 5c07a92502..c3ea4c41e4 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -343,10 +343,11 @@ static void init_ardupilot() reset_control_switch(); #if HIL_MODE != HIL_MODE_ATTITUDE - dcm.kp_roll_pitch(0.030000); + dcm.kp_roll_pitch(0.130000); dcm.ki_roll_pitch(0.00001278), // 50 hz I term dcm.kp_yaw(0.08); dcm.ki_yaw(0.00004); + dcm._clamp = 5; #endif // init the Z damopener