From 0fcf07fde76c158cc3e0b5f7da02a68fb92e3ae3 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Sat, 2 Jun 2018 14:12:09 -0700 Subject: [PATCH] RC_Channel: Remove input() method from individual channels --- libraries/RC_Channel/RC_Channel.cpp | 6 ------ libraries/RC_Channel/RC_Channel.h | 3 --- 2 files changed, 9 deletions(-) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 17855593e6..2b1e20e854 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -319,12 +319,6 @@ RC_Channel::percent_input() return ret; } -void -RC_Channel::input() -{ - radio_in = hal.rcin->read(ch_in); -} - uint16_t RC_Channel::read() const { diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index 3837e861ac..9c1c8f2ca9 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -68,9 +68,6 @@ public: // read the input value from hal.rcin for this channel uint16_t read() const; - // read input from hal.rcin and set as pwm input for channel - void input(); - static const struct AP_Param::GroupInfo var_info[]; // return true if input is within deadzone of trim