mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
AP_TECS: for _DT to at most 0.1
This commit is contained in:
parent
6c7d160ee6
commit
904e6b5b8f
@ -558,6 +558,8 @@ void AP_TECS::_initialise_states(int32_t ptchMinCO_cd)
|
|||||||
_TAS_dem_adj = _TAS_dem;
|
_TAS_dem_adj = _TAS_dem;
|
||||||
_underspeed = false;
|
_underspeed = false;
|
||||||
_badDescent = false;
|
_badDescent = false;
|
||||||
|
_DT = 0.1f; // when first starting TECS, use a
|
||||||
|
// small time constant
|
||||||
}
|
}
|
||||||
else if (_climbOutDem)
|
else if (_climbOutDem)
|
||||||
{
|
{
|
||||||
|
Loading…
Reference in New Issue
Block a user