Copter: Report what channel is used for rudder arming
This commit is contained in:
parent
9600eea394
commit
132fe82ad2
@ -57,6 +57,10 @@ bool RC_Channels_Copter::has_valid_input() const
|
||||
return true;
|
||||
}
|
||||
|
||||
RC_Channel * RC_Channels_Copter::get_arming_channel(void) const
|
||||
{
|
||||
return copter.channel_yaw;
|
||||
}
|
||||
|
||||
// init_aux_switch_function - initialize aux functions
|
||||
void RC_Channel_Copter::init_aux_function(const aux_func_t ch_option, const aux_switch_pos_t ch_flag)
|
||||
|
@ -31,6 +31,8 @@ public:
|
||||
|
||||
bool has_valid_input() const override;
|
||||
|
||||
RC_Channel *get_arming_channel(void) const override;
|
||||
|
||||
RC_Channel_Copter obj_channels[NUM_RC_CHANNELS];
|
||||
RC_Channel_Copter *channel(const uint8_t chan) override {
|
||||
if (chan >= NUM_RC_CHANNELS) {
|
||||
|
Loading…
Reference in New Issue
Block a user