mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: prevent wind up of Q-mode velocity controller I term
This commit is contained in:
parent
b3a1807349
commit
7bbd0ed74e
@ -2244,6 +2244,10 @@ void QuadPlane::run_xy_controller(float accel_limit)
|
||||
pos_control->init_xy_controller();
|
||||
}
|
||||
pos_control->set_lean_angle_max_cd(MIN(4500, MAX(accel_to_angle(accel_limit)*100, aparm.angle_max)));
|
||||
if (q_fwd_throttle > 0.95f) {
|
||||
// prevent wind up of the velocity controller I term due to a saturated forward throttle
|
||||
pos_control->set_externally_limited_xy();
|
||||
}
|
||||
pos_control->update_xy_controller();
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user