From 54c827a7928b1301fd77c2d5ba5852e8b4ed6ea9 Mon Sep 17 00:00:00 2001 From: Dan Laks Date: Fri, 10 Jul 2020 13:36:35 -0700 Subject: [PATCH] AP_ICEngine: Initialize start_chan_last_value and catch RC values less than 800 --- libraries/AP_ICEngine/AP_ICEngine.cpp | 2 +- libraries/AP_ICEngine/AP_ICEngine.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_ICEngine/AP_ICEngine.cpp b/libraries/AP_ICEngine/AP_ICEngine.cpp index b45d4889ba..24af778cc8 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.cpp +++ b/libraries/AP_ICEngine/AP_ICEngine.cpp @@ -171,7 +171,7 @@ void AP_ICEngine::update(void) // while ignoring tiny noise if (cvalue >= 1700) { cvalue = 2000; - } else if (cvalue <= 1300) { + } else if ((cvalue > 800) && (cvalue <= 1300)) { cvalue = 1300; } else { cvalue = 1500; diff --git a/libraries/AP_ICEngine/AP_ICEngine.h b/libraries/AP_ICEngine/AP_ICEngine.h index 4ce28e6d40..db3067fa3e 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.h +++ b/libraries/AP_ICEngine/AP_ICEngine.h @@ -123,7 +123,7 @@ private: AP_Int16 options; // start_chan debounce - uint16_t start_chan_last_value; + uint16_t start_chan_last_value = 1500; uint32_t start_chan_last_ms; };