From 18e55b9d6efcfca8a2cf6f1088ef9aba330d905f Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 28 Apr 2023 10:38:54 +1000 Subject: [PATCH] AP_RCProtocol: add and use AP_RCPROTOCOL_SBUS_ENABLED --- libraries/AP_RCProtocol/AP_RCProtocol.cpp | 8 ++++++++ libraries/AP_RCProtocol/AP_RCProtocol.h | 8 ++++++++ libraries/AP_RCProtocol/AP_RCProtocol_SBUS.cpp | 6 ++++++ libraries/AP_RCProtocol/AP_RCProtocol_SBUS.h | 6 ++++++ libraries/AP_RCProtocol/AP_RCProtocol_config.h | 17 +++++++++++++---- 5 files changed, 41 insertions(+), 4 deletions(-) diff --git a/libraries/AP_RCProtocol/AP_RCProtocol.cpp b/libraries/AP_RCProtocol/AP_RCProtocol.cpp index df5cb88dcc..1c1cc1cc4f 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol.cpp @@ -37,7 +37,9 @@ void AP_RCProtocol::init() { backend[AP_RCProtocol::PPM] = new AP_RCProtocol_PPMSum(*this); backend[AP_RCProtocol::IBUS] = new AP_RCProtocol_IBUS(*this); +#if AP_RCPROTOCOL_SBUS_ENABLED backend[AP_RCProtocol::SBUS] = new AP_RCProtocol_SBUS(*this, true, 100000); +#endif #if AP_RCPROTOCOL_FASTSBUS_ENABLED backend[AP_RCProtocol::FASTSBUS] = new AP_RCProtocol_SBUS(*this, true, 200000); #endif @@ -47,7 +49,9 @@ void AP_RCProtocol::init() backend[AP_RCProtocol::SRXL] = new AP_RCProtocol_SRXL(*this); #endif #ifndef IOMCU_FW +#if AP_RCPROTOCOL_SBUS_NI_ENABLED backend[AP_RCProtocol::SBUS_NI] = new AP_RCProtocol_SBUS(*this, false, 100000); +#endif #if AP_RCPROTOCOL_SRXL2_ENABLED backend[AP_RCProtocol::SRXL2] = new AP_RCProtocol_SRXL2(*this); #endif @@ -413,8 +417,12 @@ const char *AP_RCProtocol::protocol_name_from_protocol(rcprotocol_t protocol) return "PPM"; case IBUS: return "IBUS"; +#if AP_RCPROTOCOL_SBUS_ENABLED case SBUS: +#endif +#if AP_RCPROTOCOL_SBUS_NI_ENABLED case SBUS_NI: +#endif return "SBUS"; #if AP_RCPROTOCOL_FASTSBUS_ENABLED case FASTSBUS: diff --git a/libraries/AP_RCProtocol/AP_RCProtocol.h b/libraries/AP_RCProtocol/AP_RCProtocol.h index ad4e1f7807..59cd5ec891 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol.h @@ -35,8 +35,12 @@ public: enum rcprotocol_t { PPM = 0, IBUS = 1, +#if AP_RCPROTOCOL_SBUS_ENABLED SBUS = 2, +#endif +#if AP_RCPROTOCOL_SBUS_NI_ENABLED SBUS_NI = 3, +#endif DSM = 4, SUMD = 5, #if AP_RCPROTOCOL_SRXL_ENABLED @@ -90,8 +94,12 @@ public: #if AP_RCPROTOCOL_FASTSBUS_ENABLED case FASTSBUS: #endif +#if AP_RCPROTOCOL_SBUS_ENABLED case SBUS: +#endif +#if AP_RCPROTOCOL_SBUS_NI_ENABLED case SBUS_NI: +#endif case PPM: #if AP_RCPROTOCOL_FPORT_ENABLED case FPORT: diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_SBUS.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_SBUS.cpp index 1ab64ffc99..94d8ce4411 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_SBUS.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_SBUS.cpp @@ -53,6 +53,10 @@ #include "AP_RCProtocol_SBUS.h" +#include "AP_RCProtocol_config.h" + +#if AP_RCPROTOCOL_SBUS_ENABLED + #define SBUS_FRAME_SIZE 25 #define SBUS_INPUT_CHANNELS 16 #define SBUS_FLAGS_BYTE 23 @@ -219,3 +223,5 @@ void AP_RCProtocol_SBUS::process_byte(uint8_t b, uint32_t baudrate) } _process_byte(AP_HAL::micros(), b); } + +#endif // AP_RCPROTOCOL_SBUS_ENABLED diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_SBUS.h b/libraries/AP_RCProtocol/AP_RCProtocol_SBUS.h index 48923d22a4..c9c43a052b 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_SBUS.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol_SBUS.h @@ -17,6 +17,10 @@ #pragma once +#include "AP_RCProtocol_config.h" + +#if AP_RCPROTOCOL_SBUS_ENABLED + #include "AP_RCProtocol.h" #include "SoftSerial.h" @@ -41,3 +45,5 @@ private: uint32_t last_byte_us; } byte_input; }; + +#endif // AP_RCPROTOCOL_SBUS_ENABLED diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_config.h b/libraries/AP_RCProtocol/AP_RCProtocol_config.h index d1e3bcdf39..d894597ed2 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_config.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol_config.h @@ -11,10 +11,6 @@ #define AP_RCPROTOCOL_CRSF_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED #endif -#ifndef AP_RCPROTOCOL_FASTSBUS_ENABLED -#define AP_RCPROTOCOL_FASTSBUS_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED -#endif - #ifndef AP_RCPROTOCOL_FPORT_ENABLED #define AP_RCPROTOCOL_FPORT_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && AP_FRSKY_SPORT_TELEM_ENABLED #endif @@ -22,6 +18,10 @@ #define AP_RCPROTOCOL_FPORT2_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && AP_FRSKY_SPORT_TELEM_ENABLED #endif +#ifndef AP_RCPROTOCOL_SBUS_ENABLED +#define AP_RCPROTOCOL_SBUS_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED +#endif + #ifndef AP_RCPROTOCOL_SRXL_ENABLED #define AP_RCPROTOCOL_SRXL_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED #endif @@ -29,3 +29,12 @@ #ifndef AP_RCPROTOCOL_SRXL2_ENABLED #define AP_RCPROTOCOL_SRXL2_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED #endif + + +#ifndef AP_RCPROTOCOL_SBUS_NI_ENABLED +#define AP_RCPROTOCOL_SBUS_NI_ENABLED AP_RCPROTOCOL_SBUS_ENABLED +#endif + +#ifndef AP_RCPROTOCOL_FASTSBUS_ENABLED +#define AP_RCPROTOCOL_FASTSBUS_ENABLED AP_RCPROTOCOL_SBUS_ENABLED +#endif