AP_RCProtocol: check for RC protocol switching enable

by default don't allow protocol switching after initial protocol is
found
This commit is contained in:
Andrew Tridgell 2021-10-11 09:33:18 +11:00 committed by Randy Mackay
parent 6c2689fef2
commit 67fd862a8c
2 changed files with 14 additions and 3 deletions

View File

@ -63,10 +63,20 @@ AP_RCProtocol::~AP_RCProtocol()
}
}
bool AP_RCProtocol::should_search(uint32_t now_ms) const
{
#ifndef IOMCU_FW
if (_detected_protocol != AP_RCProtocol::NONE && !rc().multiple_receiver_support()) {
return false;
}
#endif
return (now_ms - _last_input_ms >= 200);
}
void AP_RCProtocol::process_pulse(uint32_t width_s0, uint32_t width_s1)
{
uint32_t now = AP_HAL::millis();
bool searching = (now - _last_input_ms >= 200);
bool searching = should_search(now);
#ifndef IOMCU_FW
rc_protocols_mask = rc().enabled_protocols();
@ -150,7 +160,7 @@ void AP_RCProtocol::process_pulse_list(const uint32_t *widths, uint16_t n, bool
bool AP_RCProtocol::process_byte(uint8_t byte, uint32_t baudrate)
{
uint32_t now = AP_HAL::millis();
bool searching = (now - _last_input_ms >= 200);
bool searching = should_search(now);
#ifndef IOMCU_FW
rc_protocols_mask = rc().enabled_protocols();
@ -234,7 +244,7 @@ void AP_RCProtocol::check_added_uart(void)
return;
}
uint32_t now = AP_HAL::millis();
bool searching = (now - _last_input_ms >= 200);
bool searching = should_search(now);
if (!searching && !_detected_with_bytes) {
// not using this uart
return;

View File

@ -49,6 +49,7 @@ public:
{
return _valid_serial_prot;
}
bool should_search(uint32_t now_ms) const;
void process_pulse(uint32_t width_s0, uint32_t width_s1);
void process_pulse_list(const uint32_t *widths, uint16_t n, bool need_swap);
bool process_byte(uint8_t byte, uint32_t baudrate);