From 132fe82ad268b8fa6017eb71290fdaa0ad468df2 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Thu, 2 Apr 2020 13:44:43 -0700 Subject: [PATCH] Copter: Report what channel is used for rudder arming --- ArduCopter/RC_Channel.cpp | 4 ++++ ArduCopter/RC_Channel.h | 2 ++ 2 files changed, 6 insertions(+) diff --git a/ArduCopter/RC_Channel.cpp b/ArduCopter/RC_Channel.cpp index 46b5a6d3cb..347f6474ea 100644 --- a/ArduCopter/RC_Channel.cpp +++ b/ArduCopter/RC_Channel.cpp @@ -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) diff --git a/ArduCopter/RC_Channel.h b/ArduCopter/RC_Channel.h index 2216e58f4f..5bbade586e 100644 --- a/ArduCopter/RC_Channel.h +++ b/ArduCopter/RC_Channel.h @@ -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) {