AP_ICEngine: Initialize start_chan_last_value and catch RC values less than 800

This commit is contained in:
Dan Laks 2020-07-10 13:36:35 -07:00 committed by Andrew Tridgell
parent 23da0ea8b6
commit 54c827a792
2 changed files with 2 additions and 2 deletions

View File

@ -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;

View File

@ -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;
};