Plane: Report what channel is used for rudder arming

This commit is contained in:
Michael du Breuil 2020-04-02 13:44:24 -07:00 committed by WickedShell
parent 2b9aa9bc21
commit 9600eea394
2 changed files with 7 additions and 0 deletions

View File

@ -27,6 +27,11 @@ bool RC_Channels_Plane::has_valid_input() const
return true;
}
RC_Channel * RC_Channels_Plane::get_arming_channel(void) const
{
return plane.channel_rudder;
}
void RC_Channel_Plane::do_aux_function_change_mode(const Mode::Number number,
const aux_switch_pos_t ch_flag)
{

View File

@ -33,6 +33,8 @@ public:
bool has_valid_input() const override;
RC_Channel *get_arming_channel(void) const override;
protected:
// note that these callbacks are not presently used on Plane: