mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AC_PosControl: update _pos_error if it is being limited
This fixes a bug that causes 10hz throttle noise.
This commit is contained in:
parent
bf68edd01c
commit
024855014f
@ -213,10 +213,12 @@ void AC_PosControl::pos_to_rate_z()
|
||||
// do not let target altitude get too far from current altitude
|
||||
if (_pos_error.z > _leash_up_z) {
|
||||
_pos_target.z = curr_alt + _leash_up_z;
|
||||
_pos_error.z = _leash_up_z;
|
||||
_limit.pos_up = true;
|
||||
}
|
||||
if (_pos_error.z < -_leash_down_z) {
|
||||
_pos_target.z = curr_alt - _leash_down_z;
|
||||
_pos_error.z = -_leash_down_z;
|
||||
_limit.pos_down = true;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user