mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: Remove input() method from individual channels
This commit is contained in:
parent
47c0048499
commit
0fcf07fde7
|
@ -319,12 +319,6 @@ RC_Channel::percent_input()
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
|
||||||
RC_Channel::input()
|
|
||||||
{
|
|
||||||
radio_in = hal.rcin->read(ch_in);
|
|
||||||
}
|
|
||||||
|
|
||||||
uint16_t
|
uint16_t
|
||||||
RC_Channel::read() const
|
RC_Channel::read() const
|
||||||
{
|
{
|
||||||
|
|
|
@ -68,9 +68,6 @@ public:
|
||||||
// read the input value from hal.rcin for this channel
|
// read the input value from hal.rcin for this channel
|
||||||
uint16_t read() const;
|
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[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
// return true if input is within deadzone of trim
|
// return true if input is within deadzone of trim
|
||||||
|
|
Loading…
Reference in New Issue