mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_RCProtocol: use switch statement for 3-frame check
Forces new protocol implementer to consider whether a 3-frame check is required
This commit is contained in:
parent
12c10dce32
commit
63f87a863c
@ -62,7 +62,24 @@ public:
|
|||||||
|
|
||||||
// for protocols without strong CRCs we require 3 good frames to lock on
|
// for protocols without strong CRCs we require 3 good frames to lock on
|
||||||
bool requires_3_frames(enum rcprotocol_t p) {
|
bool requires_3_frames(enum rcprotocol_t p) {
|
||||||
return (p == DSM || p == SBUS || p == SBUS_NI || p == PPM || p == FPORT || p == FPORT2);
|
switch (p) {
|
||||||
|
case DSM:
|
||||||
|
case SBUS:
|
||||||
|
case SBUS_NI:
|
||||||
|
case PPM:
|
||||||
|
case FPORT:
|
||||||
|
case FPORT2:
|
||||||
|
return true;
|
||||||
|
case IBUS:
|
||||||
|
case SUMD:
|
||||||
|
case SRXL:
|
||||||
|
case SRXL2:
|
||||||
|
case CRSF:
|
||||||
|
case ST24:
|
||||||
|
case NONE:
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t num_channels();
|
uint8_t num_channels();
|
||||||
|
Loading…
Reference in New Issue
Block a user