From 3e8e846d1d98241913179f91f2ef99e96c9da0d2 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Mon, 3 Oct 2022 19:18:00 +0100 Subject: [PATCH] AP_TECS: reset vdot filter if not been called --- libraries/AP_TECS/AP_TECS.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_TECS/AP_TECS.cpp b/libraries/AP_TECS/AP_TECS.cpp index 45abcbad13..ade5870c35 100644 --- a/libraries/AP_TECS/AP_TECS.cpp +++ b/libraries/AP_TECS/AP_TECS.cpp @@ -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;