diff --git a/libraries/AP_HAL_AVR/RCOutput_APM1.cpp b/libraries/AP_HAL_AVR/RCOutput_APM1.cpp
index aaef6ff7f7b052d9d988ccbf699708bad2832dc7..6cc182899afd873b1a4d1d9ea324db0c6fe8515d 100644
--- a/libraries/AP_HAL_AVR/RCOutput_APM1.cpp
+++ b/libraries/AP_HAL_AVR/RCOutput_APM1.cpp
@@ -146,14 +146,6 @@ void APM1RCOutput::disable_ch(uint8_t ch) {
     }
 }
 
-void APM1RCOutput::disable_mask(uint32_t chmask) {
-    for (int i = 0; i < 32; i++) {
-        if ((chmask >> i) & 1) {
-            disable_ch(i);
-        }
-    }
-}
-
 /* constrain pwm to be between min and max pulsewidth. */
 static inline uint16_t constrain_period(uint16_t p) {
     if (p > RC_INPUT_MAX_PULSEWIDTH) return RC_INPUT_MAX_PULSEWIDTH;
diff --git a/libraries/AP_HAL_AVR/RCOutput_APM2.cpp b/libraries/AP_HAL_AVR/RCOutput_APM2.cpp
index 1fc1978a1343e794b6e17ec4843ed1436fff9509..259c4bf3365fbcab074283d6ca8865d799a72af8 100644
--- a/libraries/AP_HAL_AVR/RCOutput_APM2.cpp
+++ b/libraries/AP_HAL_AVR/RCOutput_APM2.cpp
@@ -138,14 +138,6 @@ void APM2RCOutput::disable_ch(uint8_t ch) {
     }
 }
 
-void APM2RCOutput::disable_mask(uint32_t chmask) {
-    for (int i = 0; i < 32; i++) {
-        if ((chmask >> i) & 1) {
-            disable_ch(i);
-        }
-    }
-}
-
 /* constrain pwm to be between min and max pulsewidth. */
 static inline uint16_t constrain_period(uint16_t p) {
     if (p > RC_INPUT_MAX_PULSEWIDTH) return RC_INPUT_MAX_PULSEWIDTH;