mirror of https://github.com/ArduPilot/ardupilot
AP_TECS: Reverted pitch limitation order
This commit is contained in:
parent
121adf5f6d
commit
68003a5eb4
|
@ -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;
|
||||
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue