From 3050c1d7654a230007fad7ecd30781266c4335e4 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Mon, 30 Jan 2012 20:53:25 -0800 Subject: [PATCH] tuning fixes --- ArduCopter/ArduCopter.pde | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 15007558bb..cdc503b89c 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1921,8 +1921,8 @@ static void tuning(){ case CH6_STABILIZE_KP: g.rc_6.set_range(0,8000); // 0 to 8 - g.pid_rate_roll.kP(tuning_value); - g.pid_rate_pitch.kP(tuning_value); + g.pi_stabilize_roll.kP(tuning_value); + g.pi_stabilize_pitch.kP(tuning_value); break; case CH6_STABILIZE_KI: @@ -1982,11 +1982,17 @@ static void tuning(){ break; case CH6_NAV_P: - g.rc_6.set_range(0,6000); + g.rc_6.set_range(0,4000); g.pid_nav_lat.kP(tuning_value); g.pid_nav_lon.kP(tuning_value); break; + case CH6_NAV_I: + g.rc_6.set_range(0,500); + g.pid_nav_lat.kI(tuning_value); + g.pid_nav_lon.kI(tuning_value); + break; + #if FRAME_CONFIG == HELI_FRAME case CH6_HELI_EXTERNAL_GYRO: g.rc_6.set_range(1000,2000);