mirror of https://github.com/ArduPilot/ardupilot
AP_RCProtocol: add separate define for AP_RCPROTOCOL_IBUS_ENABLED
This commit is contained in:
parent
1b040fa0c3
commit
c9b39c6d32
|
@ -44,7 +44,9 @@ void AP_RCProtocol::init()
|
|||
#if AP_RCPROTOCOL_PPMSUM_ENABLED
|
||||
backend[AP_RCProtocol::PPMSUM] = new AP_RCProtocol_PPMSum(*this);
|
||||
#endif
|
||||
#if AP_RCPROTOCOL_IBUS_ENABLED
|
||||
backend[AP_RCProtocol::IBUS] = new AP_RCProtocol_IBUS(*this);
|
||||
#endif
|
||||
#if AP_RCPROTOCOL_SBUS_ENABLED
|
||||
backend[AP_RCProtocol::SBUS] = new AP_RCProtocol_SBUS(*this, true, 100000);
|
||||
#endif
|
||||
|
@ -427,8 +429,10 @@ const char *AP_RCProtocol::protocol_name_from_protocol(rcprotocol_t protocol)
|
|||
case PPMSUM:
|
||||
return "PPM";
|
||||
#endif
|
||||
#if AP_RCPROTOCOL_IBUS_ENABLED
|
||||
case IBUS:
|
||||
return "IBUS";
|
||||
#endif
|
||||
#if AP_RCPROTOCOL_SBUS_ENABLED
|
||||
case SBUS:
|
||||
return "SBUS";
|
||||
|
|
|
@ -33,7 +33,9 @@ public:
|
|||
#if AP_RCPROTOCOL_PPMSUM_ENABLED
|
||||
PPMSUM = 0,
|
||||
#endif
|
||||
#if AP_RCPROTOCOL_IBUS_ENABLED
|
||||
IBUS = 1,
|
||||
#endif
|
||||
#if AP_RCPROTOCOL_SBUS_ENABLED
|
||||
SBUS = 2,
|
||||
#endif
|
||||
|
@ -124,7 +126,9 @@ public:
|
|||
case CRSF:
|
||||
#endif
|
||||
return true;
|
||||
#if AP_RCPROTOCOL_IBUS_ENABLED
|
||||
case IBUS:
|
||||
#endif
|
||||
case SUMD:
|
||||
#if AP_RCPROTOCOL_SRXL_ENABLED
|
||||
case SRXL:
|
||||
|
|
|
@ -16,7 +16,7 @@
|
|||
|
||||
#include "AP_RCProtocol_config.h"
|
||||
|
||||
#if AP_RCPROTOCOL_ENABLED
|
||||
#if AP_RCPROTOCOL_IBUS_ENABLED
|
||||
|
||||
#include "AP_RCProtocol_IBUS.h"
|
||||
|
||||
|
@ -110,4 +110,4 @@ void AP_RCProtocol_IBUS::process_byte(uint8_t b, uint32_t baudrate)
|
|||
_process_byte(AP_HAL::micros(), b);
|
||||
}
|
||||
|
||||
#endif // AP_RCPROTOCOL_ENABLED
|
||||
#endif // AP_RCPROTOCOL_IBUS_ENABLED
|
||||
|
|
|
@ -18,7 +18,7 @@
|
|||
|
||||
#include "AP_RCProtocol_config.h"
|
||||
|
||||
#if AP_RCPROTOCOL_ENABLED
|
||||
#if AP_RCPROTOCOL_IBUS_ENABLED
|
||||
|
||||
#define IBUS_FRAME_SIZE 32
|
||||
#define IBUS_INPUT_CHANNELS 14
|
||||
|
@ -46,4 +46,4 @@ private:
|
|||
} byte_input;
|
||||
};
|
||||
|
||||
#endif // AP_RCPROTOCOL_ENABLED
|
||||
#endif // AP_RCPROTOCOL_IBUS_ENABLED
|
||||
|
|
|
@ -22,6 +22,10 @@
|
|||
#define AP_RCPROTOCOL_FPORT2_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && AP_FRSKY_SPORT_TELEM_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RCPROTOCOL_IBUS_ENABLED
|
||||
#define AP_RCPROTOCOL_IBUS_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RCPROTOCOL_PPMSUM_ENABLED
|
||||
#define AP_RCPROTOCOL_PPMSUM_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue