From 87cc95dd7fc94d0fddbfb865b8f0e71634731572 Mon Sep 17 00:00:00 2001
From: Andrew Tridgell <tridge@samba.org>
Date: Thu, 16 Jan 2014 17:16:17 +1100
Subject: [PATCH] AP_HAL: removed unused enable_mask and disable_mask functions

---
 libraries/AP_HAL/RCOutput.h                    |  3 ---
 libraries/AP_HAL_AVR/RCOutput.h                |  6 ------
 libraries/AP_HAL_AVR/RCOutput_APM1.cpp         |  8 --------
 libraries/AP_HAL_AVR/RCOutput_APM2.cpp         |  9 ---------
 .../RCPassthroughTest/RCPassthroughTest.pde    |  4 +++-
 libraries/AP_HAL_AVR_SITL/RCOutput.cpp         |  6 ------
 libraries/AP_HAL_AVR_SITL/RCOutput.h           |  2 --
 libraries/AP_HAL_Empty/RCOutput.cpp            |  6 ------
 libraries/AP_HAL_Empty/RCOutput.h              |  2 --
 libraries/AP_HAL_FLYMAPLE/RCOutput.cpp         | 18 ------------------
 libraries/AP_HAL_FLYMAPLE/RCOutput.h           |  2 --
 .../RCPassthroughTest/RCPassthroughTest.pde    |  4 +++-
 libraries/AP_HAL_Linux/RCOutput.cpp            |  6 ------
 libraries/AP_HAL_Linux/RCOutput.h              |  2 --
 libraries/AP_HAL_PX4/RCOutput.cpp              | 10 ----------
 libraries/AP_HAL_PX4/RCOutput.h                |  2 --
 16 files changed, 6 insertions(+), 84 deletions(-)

diff --git a/libraries/AP_HAL/RCOutput.h b/libraries/AP_HAL/RCOutput.h
index 2ad4b97fff..19eb10368a 100644
--- a/libraries/AP_HAL/RCOutput.h
+++ b/libraries/AP_HAL/RCOutput.h
@@ -32,10 +32,7 @@ public:
     /* Output active/highZ control, either by single channel at a time
      * or a mask of channels */
     virtual void     enable_ch(uint8_t ch) = 0;
-    virtual void     enable_mask(uint32_t chmask) = 0;
-
     virtual void     disable_ch(uint8_t ch) = 0;
-    virtual void     disable_mask(uint32_t chmask) = 0;
 
     /* Output, either single channel or bulk array of channels */
     virtual void     write(uint8_t ch, uint16_t period_us) = 0;
diff --git a/libraries/AP_HAL_AVR/RCOutput.h b/libraries/AP_HAL_AVR/RCOutput.h
index 3b166214d4..c81e370505 100644
--- a/libraries/AP_HAL_AVR/RCOutput.h
+++ b/libraries/AP_HAL_AVR/RCOutput.h
@@ -17,10 +17,7 @@ public:
     /* Output active/highZ control, either by single channel at a time
      * or a mask of channels */
     void     enable_ch(uint8_t ch);
-    void     enable_mask(uint32_t chmask);
-
     void     disable_ch(uint8_t ch);
-    void     disable_mask(uint32_t chmask);
 
     /* Output, either single channel or bulk array of channels */
     void     write(uint8_t ch, uint16_t period_ms);
@@ -47,10 +44,7 @@ public:
     /* Output active/highZ control, either by single channel at a time
      * or a mask of channels */
     void     enable_ch(uint8_t ch);
-    void     enable_mask(uint32_t chmask);
-
     void     disable_ch(uint8_t ch);
-    void     disable_mask(uint32_t chmask);
 
     /* Output, either single channel or bulk array of channels */
     void     write(uint8_t ch, uint16_t period_us);
diff --git a/libraries/AP_HAL_AVR/RCOutput_APM1.cpp b/libraries/AP_HAL_AVR/RCOutput_APM1.cpp
index c2f1b109f9..aaef6ff7f7 100644
--- a/libraries/AP_HAL_AVR/RCOutput_APM1.cpp
+++ b/libraries/AP_HAL_AVR/RCOutput_APM1.cpp
@@ -130,14 +130,6 @@ void APM1RCOutput::enable_ch(uint8_t ch) {
     }
 }
 
-void APM1RCOutput::enable_mask(uint32_t chmask) {
-    for (int i = 0; i < 32; i++) {
-        if ((chmask >> i) & 1) {
-            enable_ch(i);
-        }
-    }
-}
-
 void APM1RCOutput::disable_ch(uint8_t ch) {
     switch(ch) {
     case 0:  TCCR5A &= ~(1<<COM5B1); break;  // CH_1 : OC5B
diff --git a/libraries/AP_HAL_AVR/RCOutput_APM2.cpp b/libraries/AP_HAL_AVR/RCOutput_APM2.cpp
index 1125baeff3..1fc1978a13 100644
--- a/libraries/AP_HAL_AVR/RCOutput_APM2.cpp
+++ b/libraries/AP_HAL_AVR/RCOutput_APM2.cpp
@@ -123,15 +123,6 @@ void APM2RCOutput::enable_ch(uint8_t ch) {
     }
 }
 
-void APM2RCOutput::enable_mask(uint32_t chmask) {
-    for (int i = 0; i < 32; i++) {
-        uint32_t c = chmask >> i;
-        if (c & 1) {
-            enable_ch(i);
-        }
-    }
-}
-
 void APM2RCOutput::disable_ch(uint8_t ch) {
     switch(ch) {
     case 0: TCCR1A &= ~(1<<COM1B1); break; // CH_1 : OC1B
diff --git a/libraries/AP_HAL_AVR/examples/RCPassthroughTest/RCPassthroughTest.pde b/libraries/AP_HAL_AVR/examples/RCPassthroughTest/RCPassthroughTest.pde
index c77e4b3e4c..f848e22c77 100644
--- a/libraries/AP_HAL_AVR/examples/RCPassthroughTest/RCPassthroughTest.pde
+++ b/libraries/AP_HAL_AVR/examples/RCPassthroughTest/RCPassthroughTest.pde
@@ -83,7 +83,9 @@ void loop (void) {
 void setup (void) {
     hal.gpio->pinMode(27, GPIO_OUTPUT);
     hal.gpio->write(27, 0);
-    hal.rcout->enable_mask(0x000000FF);
+    for (uint8_t i=0; i<16; i++) {
+        hal.rcout->enable_ch(i);
+    }
 
     /* Bottom 4 channels at 400hz (like on a quad) */
     hal.rcout->set_freq(0x0000000F, 400);
diff --git a/libraries/AP_HAL_AVR_SITL/RCOutput.cpp b/libraries/AP_HAL_AVR_SITL/RCOutput.cpp
index 784605773c..36189f3090 100644
--- a/libraries/AP_HAL_AVR_SITL/RCOutput.cpp
+++ b/libraries/AP_HAL_AVR_SITL/RCOutput.cpp
@@ -18,15 +18,9 @@ uint16_t SITLRCOutput::get_freq(uint8_t ch) {
 void SITLRCOutput::enable_ch(uint8_t ch)
 {}
 
-void SITLRCOutput::enable_mask(uint32_t chmask)
-{}
-
 void SITLRCOutput::disable_ch(uint8_t ch)
 {}
 
-void SITLRCOutput::disable_mask(uint32_t chmask)
-{}
-
 void SITLRCOutput::write(uint8_t ch, uint16_t period_us)
 {
 	_sitlState->pwm_output[ch] = period_us;
diff --git a/libraries/AP_HAL_AVR_SITL/RCOutput.h b/libraries/AP_HAL_AVR_SITL/RCOutput.h
index 7241ece63d..7604ab6c5e 100644
--- a/libraries/AP_HAL_AVR_SITL/RCOutput.h
+++ b/libraries/AP_HAL_AVR_SITL/RCOutput.h
@@ -16,9 +16,7 @@ public:
     void     set_freq(uint32_t chmask, uint16_t freq_hz);
     uint16_t get_freq(uint8_t ch);
     void     enable_ch(uint8_t ch);
-    void     enable_mask(uint32_t chmask);
     void     disable_ch(uint8_t ch);
-    void     disable_mask(uint32_t chmask);
     void     write(uint8_t ch, uint16_t period_us);
     void     write(uint8_t ch, uint16_t* period_us, uint8_t len);
     uint16_t read(uint8_t ch);
diff --git a/libraries/AP_HAL_Empty/RCOutput.cpp b/libraries/AP_HAL_Empty/RCOutput.cpp
index 9a1c14ccea..ca8c66a34a 100644
--- a/libraries/AP_HAL_Empty/RCOutput.cpp
+++ b/libraries/AP_HAL_Empty/RCOutput.cpp
@@ -14,15 +14,9 @@ uint16_t EmptyRCOutput::get_freq(uint8_t ch) {
 void EmptyRCOutput::enable_ch(uint8_t ch)
 {}
 
-void EmptyRCOutput::enable_mask(uint32_t chmask)
-{}
-
 void EmptyRCOutput::disable_ch(uint8_t ch)
 {}
 
-void EmptyRCOutput::disable_mask(uint32_t chmask)
-{}
-
 void EmptyRCOutput::write(uint8_t ch, uint16_t period_us)
 {}
 
diff --git a/libraries/AP_HAL_Empty/RCOutput.h b/libraries/AP_HAL_Empty/RCOutput.h
index 92e0b94148..77f6ea6b3e 100644
--- a/libraries/AP_HAL_Empty/RCOutput.h
+++ b/libraries/AP_HAL_Empty/RCOutput.h
@@ -9,9 +9,7 @@ class Empty::EmptyRCOutput : public AP_HAL::RCOutput {
     void     set_freq(uint32_t chmask, uint16_t freq_hz);
     uint16_t get_freq(uint8_t ch);
     void     enable_ch(uint8_t ch);
-    void     enable_mask(uint32_t chmask);
     void     disable_ch(uint8_t ch);
-    void     disable_mask(uint32_t chmask);
     void     write(uint8_t ch, uint16_t period_us);
     void     write(uint8_t ch, uint16_t* period_us, uint8_t len);
     uint16_t read(uint8_t ch);
diff --git a/libraries/AP_HAL_FLYMAPLE/RCOutput.cpp b/libraries/AP_HAL_FLYMAPLE/RCOutput.cpp
index f9dbf86c09..fdcd1e6132 100644
--- a/libraries/AP_HAL_FLYMAPLE/RCOutput.cpp
+++ b/libraries/AP_HAL_FLYMAPLE/RCOutput.cpp
@@ -71,15 +71,6 @@ void FLYMAPLERCOutput::enable_ch(uint8_t ch)
     write(ch, 0);
 }
 
-void FLYMAPLERCOutput::enable_mask(uint32_t chmask)
-{
-    for (int i = 0; i < 32; i++) {
-        if ((chmask >> i) & 1) {
-            enable_ch(i);
-        }
-    }
-}
-
 void FLYMAPLERCOutput::disable_ch(uint8_t ch)
 {
     if (ch >= FLYMAPLE_RC_OUTPUT_NUM_CHANNELS)
@@ -87,15 +78,6 @@ void FLYMAPLERCOutput::disable_ch(uint8_t ch)
     // TODO
 }
 
-void FLYMAPLERCOutput::disable_mask(uint32_t chmask)
-{
-    for (int i = 0; i < 32; i++) {
-        if ((chmask >> i) & 1) {
-            disable_ch(i);
-        }
-    }
-}
-
 void FLYMAPLERCOutput::write(uint8_t ch, uint16_t period_us)
 {
     if (ch >= FLYMAPLE_RC_OUTPUT_NUM_CHANNELS)
diff --git a/libraries/AP_HAL_FLYMAPLE/RCOutput.h b/libraries/AP_HAL_FLYMAPLE/RCOutput.h
index 7066c017f2..2f2bf19a6b 100644
--- a/libraries/AP_HAL_FLYMAPLE/RCOutput.h
+++ b/libraries/AP_HAL_FLYMAPLE/RCOutput.h
@@ -28,9 +28,7 @@ class AP_HAL_FLYMAPLE_NS::FLYMAPLERCOutput : public AP_HAL::RCOutput {
     void     set_freq(uint32_t chmask, uint16_t freq_hz);
     uint16_t get_freq(uint8_t ch);
     void     enable_ch(uint8_t ch);
-    void     enable_mask(uint32_t chmask);
     void     disable_ch(uint8_t ch);
-    void     disable_mask(uint32_t chmask);
     void     write(uint8_t ch, uint16_t period_us);
     void     write(uint8_t ch, uint16_t* period_us, uint8_t len);
     uint16_t read(uint8_t ch);
diff --git a/libraries/AP_HAL_FLYMAPLE/examples/RCPassthroughTest/RCPassthroughTest.pde b/libraries/AP_HAL_FLYMAPLE/examples/RCPassthroughTest/RCPassthroughTest.pde
index 422b795fbe..411d47b9de 100644
--- a/libraries/AP_HAL_FLYMAPLE/examples/RCPassthroughTest/RCPassthroughTest.pde
+++ b/libraries/AP_HAL_FLYMAPLE/examples/RCPassthroughTest/RCPassthroughTest.pde
@@ -80,7 +80,9 @@ void setup (void) {
 //    hal.scheduler->delay(5000);
     hal.gpio->pinMode(13, GPIO_OUTPUT);
     hal.gpio->write(13, 0);
-    hal.rcout->enable_mask(0x000000FF);
+    for (uint8_t i=0; i<16; i++) {
+        hal.rcout->enable_ch(i);
+    }
 
     /* Bottom 4 channels at 400hz (like on a quad) */
     hal.rcout->set_freq(0x0000000F, 400);
diff --git a/libraries/AP_HAL_Linux/RCOutput.cpp b/libraries/AP_HAL_Linux/RCOutput.cpp
index 80fff7b099..5a03d1ee27 100644
--- a/libraries/AP_HAL_Linux/RCOutput.cpp
+++ b/libraries/AP_HAL_Linux/RCOutput.cpp
@@ -17,15 +17,9 @@ uint16_t LinuxRCOutput::get_freq(uint8_t ch) {
 void LinuxRCOutput::enable_ch(uint8_t ch)
 {}
 
-void LinuxRCOutput::enable_mask(uint32_t chmask)
-{}
-
 void LinuxRCOutput::disable_ch(uint8_t ch)
 {}
 
-void LinuxRCOutput::disable_mask(uint32_t chmask)
-{}
-
 void LinuxRCOutput::write(uint8_t ch, uint16_t period_us)
 {}
 
diff --git a/libraries/AP_HAL_Linux/RCOutput.h b/libraries/AP_HAL_Linux/RCOutput.h
index 84e1524826..b46b3c434b 100644
--- a/libraries/AP_HAL_Linux/RCOutput.h
+++ b/libraries/AP_HAL_Linux/RCOutput.h
@@ -9,9 +9,7 @@ class Linux::LinuxRCOutput : public AP_HAL::RCOutput {
     void     set_freq(uint32_t chmask, uint16_t freq_hz);
     uint16_t get_freq(uint8_t ch);
     void     enable_ch(uint8_t ch);
-    void     enable_mask(uint32_t chmask);
     void     disable_ch(uint8_t ch);
-    void     disable_mask(uint32_t chmask);
     void     write(uint8_t ch, uint16_t period_us);
     void     write(uint8_t ch, uint16_t* period_us, uint8_t len);
     uint16_t read(uint8_t ch);
diff --git a/libraries/AP_HAL_PX4/RCOutput.cpp b/libraries/AP_HAL_PX4/RCOutput.cpp
index a00454599d..4800929ca1 100644
--- a/libraries/AP_HAL_PX4/RCOutput.cpp
+++ b/libraries/AP_HAL_PX4/RCOutput.cpp
@@ -133,21 +133,11 @@ void PX4RCOutput::enable_ch(uint8_t ch)
     // channels are always enabled ...
 }
 
-void PX4RCOutput::enable_mask(uint32_t chmask)
-{
-    // channels are always enabled ...
-}
-
 void PX4RCOutput::disable_ch(uint8_t ch)
 {
     // channels are always enabled ...
 }
 
-void PX4RCOutput::disable_mask(uint32_t chmask)
-{
-    // channels are always enabled ...
-}
-
 void PX4RCOutput::set_safety_pwm(uint32_t chmask, uint16_t period_us)
 {
     struct pwm_output_values pwm_values;
diff --git a/libraries/AP_HAL_PX4/RCOutput.h b/libraries/AP_HAL_PX4/RCOutput.h
index 10f9bed0d1..33cadd06fb 100644
--- a/libraries/AP_HAL_PX4/RCOutput.h
+++ b/libraries/AP_HAL_PX4/RCOutput.h
@@ -14,9 +14,7 @@ public:
     void     set_freq(uint32_t chmask, uint16_t freq_hz);
     uint16_t get_freq(uint8_t ch);
     void     enable_ch(uint8_t ch);
-    void     enable_mask(uint32_t chmask);
     void     disable_ch(uint8_t ch);
-    void     disable_mask(uint32_t chmask);
     void     write(uint8_t ch, uint16_t period_us);
     void     write(uint8_t ch, uint16_t* period_us, uint8_t len);
     uint16_t read(uint8_t ch);