5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-05 15:38:29 -04:00

AP_RCProtocol: add and use AP_RCPROTOCOL_SBUS_ENABLED

This commit is contained in:
Peter Barker 2023-04-28 10:38:54 +10:00 committed by Andrew Tridgell
parent 0cab4c7ebf
commit 18e55b9d6e
5 changed files with 41 additions and 4 deletions

View File

@ -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:

View File

@ -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:

View File

@ -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

View File

@ -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

View File

@ -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