mirror of https://github.com/ArduPilot/ardupilot
AP_RCProtocol: add separate define for AP_RCPROTOCOL_DSM_ENABLED
This commit is contained in:
parent
e3d00f20a6
commit
8cc662163b
|
@ -55,7 +55,9 @@ void AP_RCProtocol::init()
|
||||||
#if AP_RCPROTOCOL_FASTSBUS_ENABLED
|
#if AP_RCPROTOCOL_FASTSBUS_ENABLED
|
||||||
backend[AP_RCProtocol::FASTSBUS] = new AP_RCProtocol_SBUS(*this, true, 200000);
|
backend[AP_RCProtocol::FASTSBUS] = new AP_RCProtocol_SBUS(*this, true, 200000);
|
||||||
#endif
|
#endif
|
||||||
|
#if AP_RCPROTOCOL_DSM_ENABLED
|
||||||
backend[AP_RCProtocol::DSM] = new AP_RCProtocol_DSM(*this);
|
backend[AP_RCProtocol::DSM] = new AP_RCProtocol_DSM(*this);
|
||||||
|
#endif
|
||||||
#if AP_RCPROTOCOL_SUMD_ENABLED
|
#if AP_RCPROTOCOL_SUMD_ENABLED
|
||||||
backend[AP_RCProtocol::SUMD] = new AP_RCProtocol_SUMD(*this);
|
backend[AP_RCProtocol::SUMD] = new AP_RCProtocol_SUMD(*this);
|
||||||
#endif
|
#endif
|
||||||
|
@ -475,8 +477,10 @@ const char *AP_RCProtocol::protocol_name_from_protocol(rcprotocol_t protocol)
|
||||||
case FASTSBUS:
|
case FASTSBUS:
|
||||||
return "FastSBUS";
|
return "FastSBUS";
|
||||||
#endif
|
#endif
|
||||||
|
#if AP_RCPROTOCOL_DSM_ENABLED
|
||||||
case DSM:
|
case DSM:
|
||||||
return "DSM";
|
return "DSM";
|
||||||
|
#endif
|
||||||
#if AP_RCPROTOCOL_SUMD_ENABLED
|
#if AP_RCPROTOCOL_SUMD_ENABLED
|
||||||
case SUMD:
|
case SUMD:
|
||||||
return "SUMD";
|
return "SUMD";
|
||||||
|
|
|
@ -42,7 +42,9 @@ public:
|
||||||
#if AP_RCPROTOCOL_SBUS_NI_ENABLED
|
#if AP_RCPROTOCOL_SBUS_NI_ENABLED
|
||||||
SBUS_NI = 3,
|
SBUS_NI = 3,
|
||||||
#endif
|
#endif
|
||||||
|
#if AP_RCPROTOCOL_DSM_ENABLED
|
||||||
DSM = 4,
|
DSM = 4,
|
||||||
|
#endif
|
||||||
#if AP_RCPROTOCOL_SUMD_ENABLED
|
#if AP_RCPROTOCOL_SUMD_ENABLED
|
||||||
SUMD = 5,
|
SUMD = 5,
|
||||||
#endif
|
#endif
|
||||||
|
@ -111,7 +113,9 @@ public:
|
||||||
// for protocols without strong CRCs we require 3 good frames to lock on
|
// for protocols without strong CRCs we require 3 good frames to lock on
|
||||||
bool requires_3_frames(enum rcprotocol_t p) {
|
bool requires_3_frames(enum rcprotocol_t p) {
|
||||||
switch (p) {
|
switch (p) {
|
||||||
|
#if AP_RCPROTOCOL_DSM_ENABLED
|
||||||
case DSM:
|
case DSM:
|
||||||
|
#endif
|
||||||
#if AP_RCPROTOCOL_FASTSBUS_ENABLED
|
#if AP_RCPROTOCOL_FASTSBUS_ENABLED
|
||||||
case FASTSBUS:
|
case FASTSBUS:
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -20,7 +20,7 @@
|
||||||
|
|
||||||
#include "AP_RCProtocol_config.h"
|
#include "AP_RCProtocol_config.h"
|
||||||
|
|
||||||
#if AP_RCPROTOCOL_ENABLED
|
#if AP_RCPROTOCOL_DSM_ENABLED
|
||||||
|
|
||||||
#include "AP_RCProtocol_DSM.h"
|
#include "AP_RCProtocol_DSM.h"
|
||||||
#include <AP_VideoTX/AP_VideoTX_config.h>
|
#include <AP_VideoTX/AP_VideoTX_config.h>
|
||||||
|
@ -539,4 +539,4 @@ void AP_RCProtocol_DSM::process_byte(uint8_t b, uint32_t baudrate)
|
||||||
_process_byte(AP_HAL::millis(), b);
|
_process_byte(AP_HAL::millis(), b);
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // AP_RCPROTOCOL_ENABLED
|
#endif // AP_RCPROTOCOL_DSM_ENABLED
|
||||||
|
|
|
@ -19,7 +19,7 @@
|
||||||
|
|
||||||
#include "AP_RCProtocol_config.h"
|
#include "AP_RCProtocol_config.h"
|
||||||
|
|
||||||
#if AP_RCPROTOCOL_ENABLED
|
#if AP_RCPROTOCOL_DSM_ENABLED
|
||||||
|
|
||||||
#include "AP_RCProtocol_Backend.h"
|
#include "AP_RCProtocol_Backend.h"
|
||||||
|
|
||||||
|
@ -83,4 +83,4 @@ private:
|
||||||
SoftSerial ss{115200, SoftSerial::SERIAL_CONFIG_8N1};
|
SoftSerial ss{115200, SoftSerial::SERIAL_CONFIG_8N1};
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_RCPROTOCOL_ENABLED
|
#endif // AP_RCPROTOCOL_DSM_ENABLED
|
||||||
|
|
|
@ -19,6 +19,10 @@
|
||||||
#define AP_RCPROTOCOL_DRONECAN_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS
|
#define AP_RCPROTOCOL_DRONECAN_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_RCPROTOCOL_DSM_ENABLED
|
||||||
|
#define AP_RCPROTOCOL_DSM_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifndef AP_RCPROTOCOL_FPORT_ENABLED
|
#ifndef AP_RCPROTOCOL_FPORT_ENABLED
|
||||||
#define AP_RCPROTOCOL_FPORT_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
#define AP_RCPROTOCOL_FPORT_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue