AC_PosControl: update _pos_error if it is being limited

This fixes a bug that causes 10hz throttle noise.
This commit is contained in:
jschall 2014-02-17 02:46:05 -08:00 committed by Randy Mackay
parent bf68edd01c
commit 024855014f
1 changed files with 2 additions and 0 deletions

View File

@ -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;
}