tuning fixes

This commit is contained in:
Jason Short 2012-01-30 20:53:25 -08:00
parent 31614c39dd
commit 5934b503b8
1 changed files with 9 additions and 3 deletions

View File

@ -1921,8 +1921,8 @@ static void tuning(){
case CH6_STABILIZE_KP: case CH6_STABILIZE_KP:
g.rc_6.set_range(0,8000); // 0 to 8 g.rc_6.set_range(0,8000); // 0 to 8
g.pid_rate_roll.kP(tuning_value); g.pi_stabilize_roll.kP(tuning_value);
g.pid_rate_pitch.kP(tuning_value); g.pi_stabilize_pitch.kP(tuning_value);
break; break;
case CH6_STABILIZE_KI: case CH6_STABILIZE_KI:
@ -1982,11 +1982,17 @@ static void tuning(){
break; break;
case CH6_NAV_P: 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_lat.kP(tuning_value);
g.pid_nav_lon.kP(tuning_value); g.pid_nav_lon.kP(tuning_value);
break; 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 #if FRAME_CONFIG == HELI_FRAME
case CH6_HELI_EXTERNAL_GYRO: case CH6_HELI_EXTERNAL_GYRO:
g.rc_6.set_range(1000,2000); g.rc_6.set_range(1000,2000);