mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: add tuning of throttle rate controller's I term (THROTTLE_KI)
This commit is contained in:
parent
dc0b35da30
commit
89e737728c
|
@ -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;
|
||||
|
|
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue