From 7cc53b6449aa116b83ed1667b839425dd2e7a480 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 7 Dec 2015 09:16:45 +1100 Subject: [PATCH] RC_Channel: setup only in or out part of channels for aux channels this allows separate use of input and output --- libraries/RC_Channel/RC_Channel_aux.cpp | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/libraries/RC_Channel/RC_Channel_aux.cpp b/libraries/RC_Channel/RC_Channel_aux.cpp index 0c873952da..656b655bc3 100644 --- a/libraries/RC_Channel/RC_Channel_aux.cpp +++ b/libraries/RC_Channel/RC_Channel_aux.cpp @@ -95,19 +95,21 @@ void RC_Channel_aux::update_aux_servo_function(void) case RC_Channel_aux::k_flap: case RC_Channel_aux::k_flap_auto: case RC_Channel_aux::k_egg_drop: - _aux_channels[i]->set_range(0,100); + _aux_channels[i]->set_range_out(0,100); + break; + case RC_Channel_aux::k_aileron_with_input: + case RC_Channel_aux::k_elevator_with_input: + _aux_channels[i]->set_angle(4500); break; case RC_Channel_aux::k_aileron: - case RC_Channel_aux::k_aileron_with_input: case RC_Channel_aux::k_elevator: - case RC_Channel_aux::k_elevator_with_input: case RC_Channel_aux::k_dspoiler1: case RC_Channel_aux::k_dspoiler2: case RC_Channel_aux::k_rudder: case RC_Channel_aux::k_steering: case RC_Channel_aux::k_flaperon1: case RC_Channel_aux::k_flaperon2: - _aux_channels[i]->set_angle(4500); + _aux_channels[i]->set_angle_out(4500); break; default: break;