mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_ICEngine: Initialize start_chan_last_value and catch RC values less than 800
This commit is contained in:
parent
23da0ea8b6
commit
54c827a792
@ -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;
|
||||
|
@ -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;
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user