mirror of https://github.com/ArduPilot/ardupilot
AP_RCProtocol: SRXL2 uses own define for max-channels
Different protocol, different count.
This commit is contained in:
parent
3ac55f97b1
commit
d5bca05fb6
|
@ -19,15 +19,13 @@
|
||||||
|
|
||||||
#include "AP_RCProtocol_config.h"
|
#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
|
#if AP_RCPROTOCOL_SRXL_ENABLED
|
||||||
|
|
||||||
#include "AP_RCProtocol.h"
|
#include "AP_RCProtocol.h"
|
||||||
#include "SoftSerial.h"
|
#include "SoftSerial.h"
|
||||||
|
|
||||||
#define SRXL_MIN_FRAMESPACE_US 8000U /* Minumum space between srxl frames in us (applies to all variants) */
|
#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 */
|
/* Variant specific SRXL datastream characteristics */
|
||||||
/* Framelength in byte */
|
/* Framelength in byte */
|
||||||
|
|
|
@ -46,7 +46,7 @@ public:
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
const uint8_t MAX_CHANNELS = MIN((uint8_t)SRXL_MAX_CHANNELS, (uint8_t)MAX_RCIN_CHANNELS);
|
const uint8_t MAX_CHANNELS = MIN((uint8_t)SRXL2_MAX_CHANNELS, (uint8_t)MAX_RCIN_CHANNELS);
|
||||||
|
|
||||||
static AP_RCProtocol_SRXL2* _singleton;
|
static AP_RCProtocol_SRXL2* _singleton;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue