mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_RCProtocol: allow switching between all protocols on IOMCU
this allows searching for uart protocols after losing a pulse based protocol
This commit is contained in:
parent
56203204cc
commit
53b6f38027
@ -40,13 +40,14 @@ void AP_RCProtocol::init()
|
||||
|
||||
void AP_RCProtocol::process_pulse(uint32_t width_s0, uint32_t width_s1)
|
||||
{
|
||||
if (_detected_protocol != AP_RCProtocol::NONE && _detected_with_bytes) {
|
||||
uint32_t now = AP_HAL::millis();
|
||||
bool searching = (now - _last_input_ms >= 200);
|
||||
if (_detected_protocol != AP_RCProtocol::NONE && _detected_with_bytes && !searching) {
|
||||
// we're using byte inputs, discard pulses
|
||||
return;
|
||||
}
|
||||
uint32_t now = AP_HAL::millis();
|
||||
// first try current protocol
|
||||
if (_detected_protocol != AP_RCProtocol::NONE && now - _last_input_ms < 200) {
|
||||
if (_detected_protocol != AP_RCProtocol::NONE && !searching) {
|
||||
backend[_detected_protocol]->process_pulse(width_s0, width_s1);
|
||||
if (backend[_detected_protocol]->new_input()) {
|
||||
_new_input = true;
|
||||
@ -70,6 +71,7 @@ void AP_RCProtocol::process_pulse(uint32_t width_s0, uint32_t width_s1)
|
||||
}
|
||||
_new_input = true;
|
||||
_detected_protocol = (enum AP_RCProtocol::rcprotocol_t)i;
|
||||
memset(_good_frames, 0, sizeof(_good_frames));
|
||||
_last_input_ms = now;
|
||||
_detected_with_bytes = false;
|
||||
}
|
||||
@ -102,13 +104,14 @@ void AP_RCProtocol::process_pulse_list(const uint32_t *widths, uint16_t n, bool
|
||||
|
||||
void AP_RCProtocol::process_byte(uint8_t byte, uint32_t baudrate)
|
||||
{
|
||||
if (_detected_protocol != AP_RCProtocol::NONE && !_detected_with_bytes) {
|
||||
uint32_t now = AP_HAL::millis();
|
||||
bool searching = (now - _last_input_ms >= 200);
|
||||
if (_detected_protocol != AP_RCProtocol::NONE && !_detected_with_bytes && !searching) {
|
||||
// we're using pulse inputs, discard bytes
|
||||
return;
|
||||
}
|
||||
uint32_t now = AP_HAL::millis();
|
||||
// first try current protocol
|
||||
if (_detected_protocol != AP_RCProtocol::NONE && now - _last_input_ms < 200) {
|
||||
if (_detected_protocol != AP_RCProtocol::NONE && !searching) {
|
||||
backend[_detected_protocol]->process_byte(byte, baudrate);
|
||||
if (backend[_detected_protocol]->new_input()) {
|
||||
_new_input = true;
|
||||
@ -128,6 +131,7 @@ void AP_RCProtocol::process_byte(uint8_t byte, uint32_t baudrate)
|
||||
}
|
||||
_new_input = true;
|
||||
_detected_protocol = (enum AP_RCProtocol::rcprotocol_t)i;
|
||||
memset(_good_frames, 0, sizeof(_good_frames));
|
||||
_last_input_ms = now;
|
||||
_detected_with_bytes = true;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user