AP_RCProtocol: factor out a poll_protocol method

This commit is contained in:
Peter Barker 2024-02-05 16:02:44 +11:00 committed by Andrew Tridgell
parent e4fc55f282
commit d37d70e787
2 changed files with 56 additions and 13 deletions

View File

@ -367,6 +367,44 @@ void AP_RCProtocol::update()
check_added_uart();
}
// explicitly investigate a backend for data, as opposed to feeding
// the backend a byte (or pulse-train) at a time and having them make
// an "add_input" callback):
bool AP_RCProtocol::detect_async_protocol(rcprotocol_t protocol)
{
auto *p = backend[protocol];
if (p == nullptr) {
// backend is not allocated?!
return false;
}
if (_detected_protocol == protocol) {
// we are using this protocol already, see if there is new
// data. Caller will handle the case where we stop presenting
// data
return p->new_input();
}
// we are not the currently in-use protocol.
const uint32_t now = AP_HAL::millis();
// see if another backend is providing data:
if (!should_search(now)) {
// apparently, yes
return false;
}
// nobody is providing data; can we provide data?
if (!p->new_input()) {
// we can't provide data
return false;
}
// we can provide data, change the detected protocol to be us:
_detected_protocol = protocol;
return true;
}
bool AP_RCProtocol::new_input()
{
// if we have an extra UART from a SERIALn_PROTOCOL then check it for data
@ -379,21 +417,21 @@ bool AP_RCProtocol::new_input()
}
}
// iterate through backends which don't do either of pulse or uart
// input, and thus won't update_new_input
const rcprotocol_t pollable[] {
#if AP_RCPROTOCOL_DRONECAN_ENABLED
uint32_t now = AP_HAL::millis();
if (should_search(now)) {
if (backend[AP_RCProtocol::DRONECAN] != nullptr &&
backend[AP_RCProtocol::DRONECAN]->new_input()) {
_detected_protocol = AP_RCProtocol::DRONECAN;
_last_input_ms = now;
}
} else if (_detected_protocol == AP_RCProtocol::DRONECAN) {
_new_input = backend[AP_RCProtocol::DRONECAN]->new_input();
if (_new_input) {
_last_input_ms = now;
}
}
AP_RCProtocol::DRONECAN,
#endif
};
for (const auto protocol : pollable) {
_new_input = detect_async_protocol(protocol);
if (!_new_input) {
continue;
}
_last_input_ms = AP_HAL::millis();
break;
}
bool ret = _new_input;
_new_input = false;

View File

@ -211,6 +211,11 @@ private:
// return true if a specific protocol is enabled
bool protocol_enabled(enum rcprotocol_t protocol) const;
// explicitly investigate a backend for data, as opposed to
// feeding the backend a byte (or pulse-train) at a time and
// having them make an "add_input" callback):
bool detect_async_protocol(rcprotocol_t protocol);
enum rcprotocol_t _detected_protocol = NONE;
uint16_t _disabled_for_pulses;
bool _detected_with_bytes;