mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: added disable_out() method
This commit is contained in:
parent
ce773f085a
commit
f6d888e0da
|
@ -382,6 +382,12 @@ RC_Channel::enable_out()
|
|||
hal.rcout->enable_ch(_ch_out);
|
||||
}
|
||||
|
||||
void
|
||||
RC_Channel::disable_out()
|
||||
{
|
||||
hal.rcout->disable_ch(_ch_out);
|
||||
}
|
||||
|
||||
RC_Channel *RC_Channel::rc_channel(uint8_t i)
|
||||
{
|
||||
if (i >= RC_MAX_CHANNELS) {
|
||||
|
|
|
@ -104,6 +104,7 @@ public:
|
|||
uint16_t read() const;
|
||||
void input();
|
||||
void enable_out();
|
||||
void disable_out();
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
|
|
Loading…
Reference in New Issue