From 9393b21a8db69a63efaf1a268e765394493ab6a5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 3 Mar 2012 13:27:29 +1100 Subject: [PATCH] ACM: adjust yaw drift correction constants this should give the compass a bit more authority --- ArduCopter/system.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index a3c43799b4..92c679a000 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -311,8 +311,8 @@ static void init_ardupilot() #if HIL_MODE != HIL_MODE_ATTITUDE 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.kp_yaw(0.12); + dcm.ki_yaw(0.00002); dcm._clamp = 5; #endif