ArduCopter: add tuning of throttle rate controller's I term (THROTTLE_KI)

This commit is contained in:
rmackay9 2012-11-25 18:02:45 +09:00
parent 7b4ed2d227
commit d7f76ebd87
2 changed files with 8 additions and 3 deletions

View File

@ -2063,6 +2063,10 @@ static void tuning(){
g.pid_throttle.kP(tuning_value);
break;
case CH6_THROTTLE_KI:
g.pid_throttle.kI(tuning_value);
break;
case CH6_TOP_BOTTOM_RATIO:
motors.top_bottom_ratio = tuning_value;
break;

View File

@ -169,9 +169,10 @@
#define CH6_YAW_RATE_KD 26
// Throttle
#define CH6_THROTTLE_KP 7
#define CH6_THR_ACCEL_KP 33
#define CH6_THR_ACCEL_KI 34
#define CH6_THR_ACCEL_KD 35
#define CH6_THROTTLE_KI 33
#define CH6_THR_ACCEL_KP 34
#define CH6_THR_ACCEL_KI 35
#define CH6_THR_ACCEL_KD 36
// Extras
#define CH6_TOP_BOTTOM_RATIO 8
#define CH6_RELAY 9