AP_RCProtocol: add option to not include SRXL in build

This commit is contained in:
Peter Barker 2023-03-14 22:18:29 +11:00 committed by Peter Barker
parent 1c5f5b6ef2
commit 9d099fbcd5
5 changed files with 34 additions and 3 deletions

View File

@ -45,7 +45,9 @@ void AP_RCProtocol::init()
#endif
backend[AP_RCProtocol::DSM] = new AP_RCProtocol_DSM(*this);
backend[AP_RCProtocol::SUMD] = new AP_RCProtocol_SUMD(*this);
#if AP_RCPROTOCOL_SRXL_ENABLED
backend[AP_RCProtocol::SRXL] = new AP_RCProtocol_SRXL(*this);
#endif
#ifndef IOMCU_FW
backend[AP_RCProtocol::SBUS_NI] = new AP_RCProtocol_SBUS(*this, false, 100000);
backend[AP_RCProtocol::SRXL2] = new AP_RCProtocol_SRXL2(*this);
@ -420,8 +422,10 @@ const char *AP_RCProtocol::protocol_name_from_protocol(rcprotocol_t protocol)
return "DSM";
case SUMD:
return "SUMD";
#if AP_RCPROTOCOL_SRXL_ENABLED
case SRXL:
return "SRXL";
#endif
case SRXL2:
return "SRXL2";
case CRSF:

View File

@ -47,7 +47,9 @@ public:
SBUS_NI = 3,
DSM = 4,
SUMD = 5,
#if AP_RCPROTOCOL_SRXL_ENABLED
SRXL = 6,
#endif
SRXL2 = 7,
CRSF = 8,
ST24 = 9,
@ -105,7 +107,9 @@ public:
return true;
case IBUS:
case SUMD:
#if AP_RCPROTOCOL_SRXL_ENABLED
case SRXL:
#endif
case SRXL2:
case ST24:
case NONE:

View File

@ -20,6 +20,10 @@
- 2016.10.23: SRXL variant V1 sucessfully (Testbench and Pixhawk/MissionPlanner) tested with RX-9-DR M-LINK (SW v1.26)
*/
#include "AP_RCProtocol_config.h"
#if AP_RCPROTOCOL_SRXL_ENABLED
#include "AP_RCProtocol_SRXL.h"
#include <AP_Math/crc.h>
#include <AP_Math/AP_Math.h>
@ -281,3 +285,5 @@ void AP_RCProtocol_SRXL::process_byte(uint8_t byte, uint32_t baudrate)
}
_process_byte(AP_HAL::micros(), byte);
}
#endif // AP_RCPROTOCOL_SRXL_ENABLED

View File

@ -17,11 +17,17 @@
#pragma once
#include "AP_RCProtocol_config.h"
// this define is out here because SRXL2 uses it - probably incorrectly
#define SRXL_MAX_CHANNELS 20U /* Maximum number of channels from srxl datastream */
#if AP_RCPROTOCOL_SRXL_ENABLED
#include "AP_RCProtocol.h"
#include "SoftSerial.h"
#define SRXL_MIN_FRAMESPACE_US 8000U /* Minumum space between srxl frames in us (applies to all variants) */
#define SRXL_MAX_CHANNELS 20U /* Maximum number of channels from srxl datastream */
/* Variant specific SRXL datastream characteristics */
/* Framelength in byte */
@ -64,3 +70,5 @@ private:
SoftSerial ss{115200, SoftSerial::SERIAL_CONFIG_8N1};
};
#endif // AP_RCPROTOCOL_SRXL_ENABLED

View File

@ -1,10 +1,19 @@
#pragma once
#include <AP_HAL/AP_HAL_Boards.h>
#include <AP_Frsky_Telem/AP_Frsky_config.h>
#ifndef AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
#define AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED 1
#endif
#ifndef AP_RCPROTOCOL_FPORT_ENABLED
#define AP_RCPROTOCOL_FPORT_ENABLED AP_FRSKY_SPORT_TELEM_ENABLED
#define AP_RCPROTOCOL_FPORT_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && AP_FRSKY_SPORT_TELEM_ENABLED
#endif
#ifndef AP_RCPROTOCOL_FPORT2_ENABLED
#define AP_RCPROTOCOL_FPORT2_ENABLED AP_FRSKY_SPORT_TELEM_ENABLED
#define AP_RCPROTOCOL_FPORT2_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && AP_FRSKY_SPORT_TELEM_ENABLED
#endif
#ifndef AP_RCPROTOCOL_SRXL_ENABLED
#define AP_RCPROTOCOL_SRXL_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
#endif