mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_SteerController: change the scaling of the D term
this should cope better with low speed
This commit is contained in:
parent
3878d9d09e
commit
3e24ff1b07
@ -129,10 +129,7 @@ int32_t AP_SteerController::get_steering_out(float desired_accel)
|
||||
_integrator = constrain_float(_integrator, -intLimScaled, intLimScaled);
|
||||
|
||||
// Calculate the demanded control surface deflection
|
||||
// Note the scaler is applied again. We want a 1/speed scaler applied to the feed-forward
|
||||
// path, but want a 1/speed^2 scaler applied to the rate error path.
|
||||
// This is because acceleration scales with speed^2, but rate scales with speed.
|
||||
_last_out = ( (rate_error * _K_D * 45.0f) + (desired_rate * kp_ff) ) * scaler + _integrator;
|
||||
_last_out = (rate_error * _K_D * 4.0f) + (desired_rate * kp_ff) * scaler + _integrator;
|
||||
|
||||
// Convert to centi-degrees and constrain
|
||||
return constrain_float(_last_out * 100, -4500, 4500);
|
||||
|
Loading…
Reference in New Issue
Block a user