AP_RCProtocol: add support for DJI Fast SBUS

It's just SBUS... but with increased opportunities for corruption
This commit is contained in:
Peter Barker 2021-11-05 16:39:56 +11:00 committed by Peter Barker
parent 0de96f3f4a
commit 409147a291
6 changed files with 38 additions and 8 deletions

View File

@ -39,12 +39,15 @@ void AP_RCProtocol::init()
{ {
backend[AP_RCProtocol::PPM] = new AP_RCProtocol_PPMSum(*this); backend[AP_RCProtocol::PPM] = new AP_RCProtocol_PPMSum(*this);
backend[AP_RCProtocol::IBUS] = new AP_RCProtocol_IBUS(*this); backend[AP_RCProtocol::IBUS] = new AP_RCProtocol_IBUS(*this);
backend[AP_RCProtocol::SBUS] = new AP_RCProtocol_SBUS(*this, true); backend[AP_RCProtocol::SBUS] = new AP_RCProtocol_SBUS(*this, true, 100000);
#if AP_RCPROTOCOL_FASTSBUS_ENABLED
backend[AP_RCProtocol::FASTSBUS] = new AP_RCProtocol_SBUS(*this, true, 200000);
#endif
backend[AP_RCProtocol::DSM] = new AP_RCProtocol_DSM(*this); backend[AP_RCProtocol::DSM] = new AP_RCProtocol_DSM(*this);
backend[AP_RCProtocol::SUMD] = new AP_RCProtocol_SUMD(*this); backend[AP_RCProtocol::SUMD] = new AP_RCProtocol_SUMD(*this);
backend[AP_RCProtocol::SRXL] = new AP_RCProtocol_SRXL(*this); backend[AP_RCProtocol::SRXL] = new AP_RCProtocol_SRXL(*this);
#ifndef IOMCU_FW #ifndef IOMCU_FW
backend[AP_RCProtocol::SBUS_NI] = new AP_RCProtocol_SBUS(*this, false); backend[AP_RCProtocol::SBUS_NI] = new AP_RCProtocol_SBUS(*this, false, 100000);
backend[AP_RCProtocol::SRXL2] = new AP_RCProtocol_SRXL2(*this); backend[AP_RCProtocol::SRXL2] = new AP_RCProtocol_SRXL2(*this);
backend[AP_RCProtocol::CRSF] = new AP_RCProtocol_CRSF(*this); backend[AP_RCProtocol::CRSF] = new AP_RCProtocol_CRSF(*this);
backend[AP_RCProtocol::FPORT2] = new AP_RCProtocol_FPort2(*this, true); backend[AP_RCProtocol::FPORT2] = new AP_RCProtocol_FPort2(*this, true);
@ -257,6 +260,10 @@ static const AP_RCProtocol::SerialConfig serial_configs[] {
{ 115200, 0, 1, true }, { 115200, 0, 1, true },
// SBUS settings, even parity, 2 stop bits: // SBUS settings, even parity, 2 stop bits:
{ 100000, 2, 2, true }, { 100000, 2, 2, true },
#if AP_RCPROTOCOL_FASTSBUS_ENABLED
// FastSBUS:
{ 200000, 2, 2, true },
#endif
// CrossFire: // CrossFire:
{ 416666, 0, 1, false }, { 416666, 0, 1, false },
}; };
@ -389,6 +396,10 @@ const char *AP_RCProtocol::protocol_name_from_protocol(rcprotocol_t protocol)
case SBUS: case SBUS:
case SBUS_NI: case SBUS_NI:
return "SBUS"; return "SBUS";
#if AP_RCPROTOCOL_FASTSBUS_ENABLED
case FASTSBUS:
return "FastSBUS";
#endif
case DSM: case DSM:
return "DSM"; return "DSM";
case SUMD: case SUMD:

View File

@ -21,6 +21,14 @@
#define MAX_RCIN_CHANNELS 18 #define MAX_RCIN_CHANNELS 18
#define MIN_RCIN_CHANNELS 5 #define MIN_RCIN_CHANNELS 5
#ifndef AP_RCPROTOCOL_FASTSBUS_ENABLED
#ifdef IOMCU_FW
#define AP_RCPROTOCOL_FASTSBUS_ENABLED 0
#else
#define AP_RCPROTOCOL_FASTSBUS_ENABLED 1
#endif
#endif
class AP_RCProtocol_Backend; class AP_RCProtocol_Backend;
class AP_RCProtocol { class AP_RCProtocol {
@ -42,6 +50,9 @@ public:
ST24 = 9, ST24 = 9,
FPORT = 10, FPORT = 10,
FPORT2 = 11, FPORT2 = 11,
#if AP_RCPROTOCOL_FASTSBUS_ENABLED
FASTSBUS = 12,
#endif
NONE //last enum always is None NONE //last enum always is None
}; };
void init(); void init();
@ -64,6 +75,9 @@ public:
bool requires_3_frames(enum rcprotocol_t p) { bool requires_3_frames(enum rcprotocol_t p) {
switch (p) { switch (p) {
case DSM: case DSM:
#if AP_RCPROTOCOL_FASTSBUS_ENABLED
case FASTSBUS:
#endif
case SBUS: case SBUS:
case SBUS_NI: case SBUS_NI:
case PPM: case PPM:

View File

@ -76,9 +76,10 @@
#endif #endif
// constructor // constructor
AP_RCProtocol_SBUS::AP_RCProtocol_SBUS(AP_RCProtocol &_frontend, bool _inverted) : AP_RCProtocol_SBUS::AP_RCProtocol_SBUS(AP_RCProtocol &_frontend, bool _inverted, uint32_t configured_baud) :
AP_RCProtocol_Backend(_frontend), AP_RCProtocol_Backend(_frontend),
inverted(_inverted) inverted(_inverted),
ss{configured_baud, SoftSerial::SERIAL_CONFIG_8E2I}
{} {}
// decode a full SBUS frame // decode a full SBUS frame
@ -211,7 +212,9 @@ void AP_RCProtocol_SBUS::_process_byte(uint32_t timestamp_us, uint8_t b)
// support byte input // support byte input
void AP_RCProtocol_SBUS::process_byte(uint8_t b, uint32_t baudrate) void AP_RCProtocol_SBUS::process_byte(uint8_t b, uint32_t baudrate)
{ {
if (baudrate != 100000) { // note that if we're here we're not actually using SoftSerial,
// but it does record our configured baud rate:
if (baudrate != ss.baud()) {
return; return;
} }
_process_byte(AP_HAL::micros(), b); _process_byte(AP_HAL::micros(), b);

View File

@ -22,7 +22,7 @@
class AP_RCProtocol_SBUS : public AP_RCProtocol_Backend { class AP_RCProtocol_SBUS : public AP_RCProtocol_Backend {
public: public:
AP_RCProtocol_SBUS(AP_RCProtocol &_frontend, bool inverted); AP_RCProtocol_SBUS(AP_RCProtocol &_frontend, bool inverted, uint32_t configured_baud);
void process_pulse(uint32_t width_s0, uint32_t width_s1) override; void process_pulse(uint32_t width_s0, uint32_t width_s1) override;
void process_byte(uint8_t byte, uint32_t baudrate) override; void process_byte(uint8_t byte, uint32_t baudrate) override;
@ -32,7 +32,7 @@ private:
bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_values); bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_values);
bool inverted; bool inverted;
SoftSerial ss{100000, SoftSerial::SERIAL_CONFIG_8E2I}; SoftSerial ss;
uint32_t saved_width; uint32_t saved_width;
struct { struct {

View File

@ -33,6 +33,8 @@ public:
return byte_timestamp_us; return byte_timestamp_us;
} }
uint32_t baud() const { return baudrate; }
private: private:
const uint32_t baudrate; const uint32_t baudrate;
const uint8_t half_bit; // width of half a bit in microseconds const uint8_t half_bit; // width of half a bit in microseconds

View File

@ -96,7 +96,7 @@ const AP_Param::GroupInfo RC_Channels::var_info[] = {
// @DisplayName: RC protocols enabled // @DisplayName: RC protocols enabled
// @Description: Bitmask of enabled RC protocols. Allows narrowing the protocol detection to only specific types of RC receivers which can avoid issues with incorrect detection. Set to 1 to enable all protocols. // @Description: Bitmask of enabled RC protocols. Allows narrowing the protocol detection to only specific types of RC receivers which can avoid issues with incorrect detection. Set to 1 to enable all protocols.
// @User: Advanced // @User: Advanced
// @Bitmask: 0:All,1:PPM,2:IBUS,3:SBUS,4:SBUS_NI,5:DSM,6:SUMD,7:SRXL,8:SRXL2,9:CRSF,10:ST24,11:FPORT,12:FPORT2 // @Bitmask: 0:All,1:PPM,2:IBUS,3:SBUS,4:SBUS_NI,5:DSM,6:SUMD,7:SRXL,8:SRXL2,9:CRSF,10:ST24,11:FPORT,12:FPORT2,13:FastSBUS
AP_GROUPINFO("_PROTOCOLS", 34, RC_CHANNELS_SUBCLASS, _protocols, 1), AP_GROUPINFO("_PROTOCOLS", 34, RC_CHANNELS_SUBCLASS, _protocols, 1),
AP_GROUPEND AP_GROUPEND