mirror of https://github.com/ArduPilot/ardupilot
AP_RCProtocol: add separate define for AP_RCPROTOCOL_PPMSUM_ENABLED
This commit is contained in:
parent
1225d4c88f
commit
1b040fa0c3
|
@ -41,7 +41,9 @@ extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
void AP_RCProtocol::init()
|
void AP_RCProtocol::init()
|
||||||
{
|
{
|
||||||
backend[AP_RCProtocol::PPM] = new AP_RCProtocol_PPMSum(*this);
|
#if AP_RCPROTOCOL_PPMSUM_ENABLED
|
||||||
|
backend[AP_RCProtocol::PPMSUM] = new AP_RCProtocol_PPMSum(*this);
|
||||||
|
#endif
|
||||||
backend[AP_RCProtocol::IBUS] = new AP_RCProtocol_IBUS(*this);
|
backend[AP_RCProtocol::IBUS] = new AP_RCProtocol_IBUS(*this);
|
||||||
#if AP_RCPROTOCOL_SBUS_ENABLED
|
#if AP_RCPROTOCOL_SBUS_ENABLED
|
||||||
backend[AP_RCProtocol::SBUS] = new AP_RCProtocol_SBUS(*this, true, 100000);
|
backend[AP_RCProtocol::SBUS] = new AP_RCProtocol_SBUS(*this, true, 100000);
|
||||||
|
@ -421,8 +423,10 @@ void AP_RCProtocol::start_bind(void)
|
||||||
const char *AP_RCProtocol::protocol_name_from_protocol(rcprotocol_t protocol)
|
const char *AP_RCProtocol::protocol_name_from_protocol(rcprotocol_t protocol)
|
||||||
{
|
{
|
||||||
switch (protocol) {
|
switch (protocol) {
|
||||||
case PPM:
|
#if AP_RCPROTOCOL_PPMSUM_ENABLED
|
||||||
|
case PPMSUM:
|
||||||
return "PPM";
|
return "PPM";
|
||||||
|
#endif
|
||||||
case IBUS:
|
case IBUS:
|
||||||
return "IBUS";
|
return "IBUS";
|
||||||
#if AP_RCPROTOCOL_SBUS_ENABLED
|
#if AP_RCPROTOCOL_SBUS_ENABLED
|
||||||
|
|
|
@ -30,7 +30,9 @@ class AP_RCProtocol {
|
||||||
public:
|
public:
|
||||||
|
|
||||||
enum rcprotocol_t {
|
enum rcprotocol_t {
|
||||||
PPM = 0,
|
#if AP_RCPROTOCOL_PPMSUM_ENABLED
|
||||||
|
PPMSUM = 0,
|
||||||
|
#endif
|
||||||
IBUS = 1,
|
IBUS = 1,
|
||||||
#if AP_RCPROTOCOL_SBUS_ENABLED
|
#if AP_RCPROTOCOL_SBUS_ENABLED
|
||||||
SBUS = 2,
|
SBUS = 2,
|
||||||
|
@ -109,7 +111,9 @@ public:
|
||||||
#if AP_RCPROTOCOL_SBUS_NI_ENABLED
|
#if AP_RCPROTOCOL_SBUS_NI_ENABLED
|
||||||
case SBUS_NI:
|
case SBUS_NI:
|
||||||
#endif
|
#endif
|
||||||
case PPM:
|
#if AP_RCPROTOCOL_PPMSUM_ENABLED
|
||||||
|
case PPMSUM:
|
||||||
|
#endif
|
||||||
#if AP_RCPROTOCOL_FPORT_ENABLED
|
#if AP_RCPROTOCOL_FPORT_ENABLED
|
||||||
case FPORT:
|
case FPORT:
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -17,7 +17,7 @@
|
||||||
|
|
||||||
#include "AP_RCProtocol_PPMSum.h"
|
#include "AP_RCProtocol_PPMSum.h"
|
||||||
|
|
||||||
#if AP_RCPROTOCOL_ENABLED
|
#if AP_RCPROTOCOL_PPMSUM_ENABLED
|
||||||
|
|
||||||
/*
|
/*
|
||||||
process a PPM-sum pulse of the given width
|
process a PPM-sum pulse of the given width
|
||||||
|
@ -66,4 +66,4 @@ void AP_RCProtocol_PPMSum::process_pulse(uint32_t width_s0, uint32_t width_s1)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // AP_RCPROTOCOL_ENABLED
|
#endif // AP_RCPROTOCOL_PPMSUM_ENABLED
|
||||||
|
|
|
@ -18,7 +18,7 @@
|
||||||
|
|
||||||
#include "AP_RCProtocol_config.h"
|
#include "AP_RCProtocol_config.h"
|
||||||
|
|
||||||
#if AP_RCPROTOCOL_ENABLED
|
#if AP_RCPROTOCOL_PPMSUM_ENABLED
|
||||||
|
|
||||||
#include "AP_RCProtocol_Backend.h"
|
#include "AP_RCProtocol_Backend.h"
|
||||||
|
|
||||||
|
@ -34,4 +34,4 @@ private:
|
||||||
} ppm_state;
|
} ppm_state;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_RCPROTOCOL_ENABLED
|
#endif // AP_RCPROTOCOL_PPMSUM_ENABLED
|
||||||
|
|
|
@ -22,6 +22,10 @@
|
||||||
#define AP_RCPROTOCOL_FPORT2_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && AP_FRSKY_SPORT_TELEM_ENABLED
|
#define AP_RCPROTOCOL_FPORT2_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && AP_FRSKY_SPORT_TELEM_ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_RCPROTOCOL_PPMSUM_ENABLED
|
||||||
|
#define AP_RCPROTOCOL_PPMSUM_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifndef AP_RCPROTOCOL_SBUS_ENABLED
|
#ifndef AP_RCPROTOCOL_SBUS_ENABLED
|
||||||
#define AP_RCPROTOCOL_SBUS_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
#define AP_RCPROTOCOL_SBUS_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue