From e870e7bd8204324f1a800e010d2df8c8bb477fa0 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 7 Mar 2012 15:12:31 +1100 Subject: [PATCH] ACM: removed the DCM tuning overrides not needed now that DCM scales with deltat --- ArduCopter/system.pde | 10 ---------- 1 file changed, 10 deletions(-) diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 1391643a85..b22f1f7a90 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -308,16 +308,6 @@ static void init_ardupilot() // --------------------------- reset_control_switch(); - #if HIL_MODE != HIL_MODE_ATTITUDE -#if QUATERNION_ENABLE == DISABLED - dcm.kp_roll_pitch(0.130000); - dcm.ki_roll_pitch(0.00001278), // 50 hz I term - dcm.kp_yaw(0.12); - dcm.ki_yaw(0.00002); - dcm._clamp = 5; -#endif - #endif - // init the Z damopener // -------------------- #if ACCEL_ALT_HOLD != 0