mirror of https://github.com/ArduPilot/ardupilot
AP_TECS: reset vdot filter if not been called
This commit is contained in:
parent
f24a8cd176
commit
3e8e846d1d
|
@ -308,6 +308,7 @@ void AP_TECS::update_50hz(void)
|
|||
_height_filter.dd_height = 0.0f;
|
||||
DT = 0.02f; // when first starting TECS, use a
|
||||
// small time constant
|
||||
_vdot_filter.reset();
|
||||
}
|
||||
_update_50hz_last_usec = now;
|
||||
|
||||
|
|
Loading…
Reference in New Issue