mirror of https://github.com/ArduPilot/ardupilot
AP_RCProtocol: correct assignment of new_input in rcprotocol detecion
caused RCP protocol detection to break for everything other than DroneCAN
This commit is contained in:
parent
b19f8ed57f
commit
26d4e0d285
|
@ -425,10 +425,10 @@ bool AP_RCProtocol::new_input()
|
|||
#endif
|
||||
};
|
||||
for (const auto protocol : pollable) {
|
||||
_new_input = detect_async_protocol(protocol);
|
||||
if (!_new_input) {
|
||||
if (!detect_async_protocol(protocol)) {
|
||||
continue;
|
||||
}
|
||||
_new_input = true;
|
||||
_last_input_ms = AP_HAL::millis();
|
||||
break;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue