mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-02 19:53:57 -04:00
APM_Control: disable integrator below minimum speed
this reduces the impact on initial takeoff
This commit is contained in:
parent
4bc913791f
commit
39bfd809c2
@ -113,7 +113,7 @@ int32_t AP_SteerController::get_steering_out_rate(float desired_rate)
|
||||
|
||||
// Multiply roll rate error by _ki_rate and integrate
|
||||
// Don't integrate if in stabilise mode as the integrator will wind up against the pilots inputs
|
||||
if (ki_rate > 0) {
|
||||
if (ki_rate > 0 && speed >= _minspeed) {
|
||||
// only integrate if gain and time step are positive.
|
||||
if (dt > 0) {
|
||||
float integrator_delta = rate_error * ki_rate * delta_time * scaler;
|
||||
|
Loading…
Reference in New Issue
Block a user