Skip to content

Commit

Permalink
AP_TECS: Reverted pitch limitation order
Browse files Browse the repository at this point in the history
  • Loading branch information
Georacer committed Sep 26, 2024
1 parent 4a3b80d commit 4c48f09
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions libraries/AP_TECS/AP_TECS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1053,6 +1053,9 @@ void AP_TECS::_update_pitch(void)
_pitch_dem_unc += (_TAS_dem_adj - _pitch_ff_v0) * _pitch_ff_k;
}

// Constrain pitch demand
_pitch_dem = constrain_float(_pitch_dem_unc, _PITCHminf, _PITCHmaxf);

// Rate limit the pitch demand to comply with specified vertical
// acceleration limit
float ptchRateIncr = _DT * _vertAccLim / _TAS_state;
Expand All @@ -1063,9 +1066,6 @@ void AP_TECS::_update_pitch(void)
_pitch_dem = _last_pitch_dem - ptchRateIncr;
}

// Constrain pitch demand
_pitch_dem = constrain_float(_pitch_dem_unc, _PITCHminf, _PITCHmaxf);

_last_pitch_dem = _pitch_dem;

#if HAL_LOGGING_ENABLED
Expand Down

0 comments on commit 4c48f09

Please sign in to comment.