mirror of https://github.com/ArduPilot/ardupilot
AP_RCProtocol: require 3 good frames for weak CRC protocols
This commit is contained in:
parent
e6cadfa2d9
commit
d87bef16a2
|
@ -64,6 +64,10 @@ void AP_RCProtocol::process_pulse(uint32_t width_s0, uint32_t width_s1)
|
|||
if (backend[i] != nullptr) {
|
||||
backend[i]->process_pulse(width_s0, width_s1);
|
||||
if (backend[i]->new_input()) {
|
||||
_good_frames[i]++;
|
||||
if (requires_3_frames((rcprotocol_t)i) && _good_frames[i] < 3) {
|
||||
continue;
|
||||
}
|
||||
_new_input = true;
|
||||
_detected_protocol = (enum AP_RCProtocol::rcprotocol_t)i;
|
||||
_last_input_ms = now;
|
||||
|
@ -95,6 +99,10 @@ void AP_RCProtocol::process_byte(uint8_t byte, uint32_t baudrate)
|
|||
if (backend[i] != nullptr) {
|
||||
backend[i]->process_byte(byte, baudrate);
|
||||
if (backend[i]->new_input()) {
|
||||
_good_frames[i]++;
|
||||
if (requires_3_frames((rcprotocol_t)i) && _good_frames[i] < 3) {
|
||||
continue;
|
||||
}
|
||||
_new_input = true;
|
||||
_detected_protocol = (enum AP_RCProtocol::rcprotocol_t)i;
|
||||
_last_input_ms = now;
|
||||
|
|
|
@ -50,6 +50,11 @@ public:
|
|||
_disabled_for_pulses |= (1U<<(uint8_t)protocol);
|
||||
}
|
||||
|
||||
// for protocols without strong CRCs we require 3 good frames to lock on
|
||||
bool requires_3_frames(enum rcprotocol_t p) {
|
||||
return (p == DSM || p == SBUS || p == SBUS_NI || p == PPM);
|
||||
}
|
||||
|
||||
enum rcprotocol_t protocol_detected()
|
||||
{
|
||||
return _detected_protocol;
|
||||
|
@ -72,6 +77,7 @@ private:
|
|||
bool _new_input = false;
|
||||
uint32_t _last_input_ms;
|
||||
bool _valid_serial_prot = false;
|
||||
uint8_t _good_frames[NONE];
|
||||
|
||||
static AP_RCProtocol *instance;
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue