From c484b9331461f89d8ed183cfa663d274990b728d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Patrick=20Jos=C3=A9=20Pereira?= Date: Wed, 3 Apr 2019 13:26:19 -0300 Subject: [PATCH] Plane: Use new RC_Channel AUX_FUNC MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Patrick José Pereira --- ArduPlane/RC_Channel.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/ArduPlane/RC_Channel.cpp b/ArduPlane/RC_Channel.cpp index 6973580aa3..bc9604102f 100644 --- a/ArduPlane/RC_Channel.cpp +++ b/ArduPlane/RC_Channel.cpp @@ -32,11 +32,11 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option, { switch(ch_option) { // the following functions do not need to be initialised: - case ARMDISARM: - case INVERTED: + case AUX_FUNC::ARMDISARM: + case AUX_FUNC::INVERTED: break; - case REVERSE_THROTTLE: + case AUX_FUNC::REVERSE_THROTTLE: plane.have_reverse_throttle_rc_option = true; // setup input throttle as a range. This is needed as init_aux_function is called // after set_control_channels() @@ -58,7 +58,7 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option, void RC_Channel_Plane::do_aux_function(const aux_func_t ch_option, const aux_switch_pos_t ch_flag) { switch(ch_option) { - case ARMDISARM: + case AUX_FUNC::ARMDISARM: // arm or disarm the vehicle switch (ch_flag) { case HIGH: @@ -72,11 +72,11 @@ void RC_Channel_Plane::do_aux_function(const aux_func_t ch_option, const aux_swi break; } break; - case INVERTED: + case AUX_FUNC::INVERTED: plane.inverted_flight = (ch_flag == HIGH); break; - case REVERSE_THROTTLE: + case AUX_FUNC::REVERSE_THROTTLE: plane.reversed_throttle = (ch_flag == HIGH); gcs().send_text(MAV_SEVERITY_INFO, "RevThrottle: %s", plane.reversed_throttle?"ENABLE":"DISABLE"); break;