RC_Channel: Remove input() method from individual channels

This commit is contained in:
Michael du Breuil 2018-06-02 14:12:09 -07:00 committed by Andrew Tridgell
parent 47c0048499
commit 0fcf07fde7
2 changed files with 0 additions and 9 deletions

View File

@ -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
{

View File

@ -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