From 0731b5cfa0d439169a5c3c2e0a1595d714bf9709 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 19 Jul 2022 19:14:29 +1000 Subject: [PATCH] AP_ICEngine: fixed RPM filter rate and plane.G_Dt AP_ICEngine runs at 10Hz, so we need to use 10 for the filter. As this runs in a constructor it also caused memoisation of the wrong AP_Scheduler _loop_period_s which resulted in plane.G_Dt always being 1/50, which is a much more serious issue this is a temporary fix, we need a better one soon --- libraries/AP_ICEngine/AP_ICEngine.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_ICEngine/AP_ICEngine.cpp b/libraries/AP_ICEngine/AP_ICEngine.cpp index 0016802cff..c212abe9d2 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.cpp +++ b/libraries/AP_ICEngine/AP_ICEngine.cpp @@ -168,7 +168,8 @@ AP_ICEngine::AP_ICEngine(const AP_RPM &_rpm) : } _singleton = this; - _rpm_filter.set_cutoff_frequency(1 / AP::scheduler().get_loop_period_s(), 0.5f); + // ICEngine runs at 10Hz + _rpm_filter.set_cutoff_frequency(10, 0.5f); } /*