mirror of https://github.com/ArduPilot/ardupilot
Refined Throttle Timer reset
Reduced Loiter I gain to decrease overshoot.
This commit is contained in:
parent
463aa0aa75
commit
5b57df5d1c
|
@ -1095,6 +1095,8 @@ void update_throttle_mode(void)
|
|||
}else{
|
||||
g.rc_3.servo_out = 0;
|
||||
}
|
||||
// reset the timer to throttle so that we never get fast I term run-ups
|
||||
throttle_timer = 0;
|
||||
break;
|
||||
|
||||
case THROTTLE_HOLD:
|
||||
|
|
|
@ -100,9 +100,17 @@ get_nav_throttle(long z_error, int target_speed)
|
|||
rate_error = target_speed - altitude_rate;
|
||||
rate_error = constrain(rate_error, -110, 110);
|
||||
|
||||
long timer = millis();
|
||||
float delta_throttle = (float)(timer - throttle_timer)/1000.0;
|
||||
throttle_timer = timer;
|
||||
float delta_throttle;
|
||||
|
||||
// is the throttle_timer uninitialized?
|
||||
if(throttle_timer == 0){
|
||||
throttle_timer = millis();
|
||||
delta_throttle = 0;
|
||||
}else{
|
||||
long timer = millis();
|
||||
delta_throttle = (float)(timer - throttle_timer)/1000.0;
|
||||
throttle_timer = timer;
|
||||
}
|
||||
|
||||
return (int)g.pi_throttle.get_pi(rate_error, delta_throttle);
|
||||
}
|
||||
|
@ -162,9 +170,6 @@ static void reset_nav(void)
|
|||
nav_throttle = 0;
|
||||
invalid_throttle = true;
|
||||
|
||||
// clear the throttle timer
|
||||
throttle_timer = millis();
|
||||
|
||||
g.pi_nav_lat.reset_I();
|
||||
g.pi_nav_lon.reset_I();
|
||||
|
||||
|
|
|
@ -485,7 +485,7 @@
|
|||
# define LOITER_P .4 //
|
||||
#endif
|
||||
#ifndef LOITER_I
|
||||
# define LOITER_I 0.04 //
|
||||
# define LOITER_I 0.01 //
|
||||
#endif
|
||||
#ifndef LOITER_IMAX
|
||||
# define LOITER_IMAX 12 // degrees°
|
||||
|
@ -513,7 +513,7 @@
|
|||
# define THROTTLE_P 0.6 //
|
||||
#endif
|
||||
#ifndef THROTTLE_I
|
||||
# define THROTTLE_I 0.03 // with 4m error, 12.5s windup
|
||||
# define THROTTLE_I 0.02 // with 4m error, 8 PWM gain/s
|
||||
#endif
|
||||
#ifndef THROTTLE_IMAX
|
||||
# define THROTTLE_IMAX 300
|
||||
|
|
Loading…
Reference in New Issue