mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_RCProtocol: add add use AP_RCPROTOCOL_SRXL2_ENABLED
This commit is contained in:
parent
feaed97601
commit
b3b46f7be6
@ -48,7 +48,9 @@ void AP_RCProtocol::init()
|
||||
#endif
|
||||
#ifndef IOMCU_FW
|
||||
backend[AP_RCProtocol::SBUS_NI] = new AP_RCProtocol_SBUS(*this, false, 100000);
|
||||
#if AP_RCPROTOCOL_SRXL2_ENABLED
|
||||
backend[AP_RCProtocol::SRXL2] = new AP_RCProtocol_SRXL2(*this);
|
||||
#endif
|
||||
backend[AP_RCProtocol::CRSF] = new AP_RCProtocol_CRSF(*this);
|
||||
#if AP_RCPROTOCOL_FPORT2_ENABLED
|
||||
backend[AP_RCProtocol::FPORT2] = new AP_RCProtocol_FPort2(*this, true);
|
||||
@ -424,8 +426,10 @@ const char *AP_RCProtocol::protocol_name_from_protocol(rcprotocol_t protocol)
|
||||
case SRXL:
|
||||
return "SRXL";
|
||||
#endif
|
||||
#if AP_RCPROTOCOL_SRXL2_ENABLED
|
||||
case SRXL2:
|
||||
return "SRXL2";
|
||||
#endif
|
||||
case CRSF:
|
||||
return "CRSF";
|
||||
case ST24:
|
||||
|
@ -42,7 +42,9 @@ public:
|
||||
#if AP_RCPROTOCOL_SRXL_ENABLED
|
||||
SRXL = 6,
|
||||
#endif
|
||||
#if AP_RCPROTOCOL_SRXL2_ENABLED
|
||||
SRXL2 = 7,
|
||||
#endif
|
||||
CRSF = 8,
|
||||
ST24 = 9,
|
||||
#if AP_RCPROTOCOL_FPORT_ENABLED
|
||||
@ -102,7 +104,9 @@ public:
|
||||
#if AP_RCPROTOCOL_SRXL_ENABLED
|
||||
case SRXL:
|
||||
#endif
|
||||
#if AP_RCPROTOCOL_SRXL2_ENABLED
|
||||
case SRXL2:
|
||||
#endif
|
||||
case ST24:
|
||||
case NONE:
|
||||
return false;
|
||||
|
@ -17,6 +17,10 @@
|
||||
Code by Andy Piper
|
||||
*/
|
||||
|
||||
#include "AP_RCProtocol_config.h"
|
||||
|
||||
#if AP_RCPROTOCOL_SRXL2_ENABLED
|
||||
|
||||
#include "AP_RCProtocol.h"
|
||||
#include "AP_RCProtocol_SRXL2.h"
|
||||
#include <AP_Math/AP_Math.h>
|
||||
@ -406,3 +410,5 @@ void srxlOnVtx(SrxlVtxData* pVtxData)
|
||||
AP_RCProtocol_Backend::configure_vtx(pVtxData->band, pVtxData->channel, pVtxData->power, pVtxData->pit);
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // AP_RCPROTOCOL_SRXL2_ENABLED
|
||||
|
@ -15,9 +15,11 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "AP_RCProtocol_config.h"
|
||||
|
||||
#if AP_RCPROTOCOL_SRXL2_ENABLED
|
||||
|
||||
#include "AP_RCProtocol.h"
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include "AP_RCProtocol_SRXL.h"
|
||||
#include "SoftSerial.h"
|
||||
|
||||
#define SRXL2_MAX_CHANNELS 32U /* Maximum number of channels from srxl2 datastream */
|
||||
@ -74,3 +76,5 @@ private:
|
||||
uint32_t _last_handshake_ms;
|
||||
uint32_t _handshake_start_ms;
|
||||
};
|
||||
|
||||
#endif // AP_RCPROTOCOL_SRXL2_ENABLED
|
||||
|
@ -21,3 +21,7 @@
|
||||
#ifndef AP_RCPROTOCOL_SRXL_ENABLED
|
||||
#define AP_RCPROTOCOL_SRXL_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RCPROTOCOL_SRXL2_ENABLED
|
||||
#define AP_RCPROTOCOL_SRXL2_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user