diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_SRXL.h b/libraries/AP_RCProtocol/AP_RCProtocol_SRXL.h
index 504f061cb1..590c8842f7 100644
--- a/libraries/AP_RCProtocol/AP_RCProtocol_SRXL.h
+++ b/libraries/AP_RCProtocol/AP_RCProtocol_SRXL.h
@@ -19,15 +19,13 @@
 
 #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
 
 #include "AP_RCProtocol.h"
 #include "SoftSerial.h"
 
 #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 */
 /* Framelength in byte */
diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_SRXL2.h b/libraries/AP_RCProtocol/AP_RCProtocol_SRXL2.h
index ca7ba5fac5..73a977b1e4 100644
--- a/libraries/AP_RCProtocol/AP_RCProtocol_SRXL2.h
+++ b/libraries/AP_RCProtocol/AP_RCProtocol_SRXL2.h
@@ -46,7 +46,7 @@ public:
 
 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;