diff --git a/ArduPlane/radio.pde b/ArduPlane/radio.pde index 6cacb73e86..674c096e25 100644 --- a/ArduPlane/radio.pde +++ b/ArduPlane/radio.pde @@ -24,10 +24,6 @@ static void init_rc_in() //set auxiliary ranges update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8); - G_RC_AUX(k_flap)->set_range(0,100); - G_RC_AUX(k_flap_auto)->set_range(0,100); - G_RC_AUX(k_aileron)->set_angle(SERVO_MAX); - G_RC_AUX(k_flaperon)->set_range(0,100); } static void init_rc_out() diff --git a/libraries/RC_Channel/RC_Channel_aux.cpp b/libraries/RC_Channel/RC_Channel_aux.cpp index 18b35ea05e..1ff7b45326 100644 --- a/libraries/RC_Channel/RC_Channel_aux.cpp +++ b/libraries/RC_Channel/RC_Channel_aux.cpp @@ -47,4 +47,9 @@ void update_aux_servo_function(RC_Channel_aux* rc_5, RC_Channel_aux* rc_6, RC_Ch g_rc_function[aux_servo_function[CH_6]] = rc_6; g_rc_function[aux_servo_function[CH_7]] = rc_7; g_rc_function[aux_servo_function[CH_8]] = rc_8; + + G_RC_AUX(k_flap)->set_range(0,100); + G_RC_AUX(k_flap_auto)->set_range(0,100); + G_RC_AUX(k_aileron)->set_angle(4500); + G_RC_AUX(k_flaperon)->set_range(0,100); } diff --git a/libraries/RC_Channel/RC_Channel_aux.h b/libraries/RC_Channel/RC_Channel_aux.h index 556ffa6c3b..7e091bf18f 100644 --- a/libraries/RC_Channel/RC_Channel_aux.h +++ b/libraries/RC_Channel/RC_Channel_aux.h @@ -14,7 +14,6 @@ /// @class RC_Channel_aux /// @brief Object managing one aux. RC channel (CH5-8), with information about its function -/// Also contains physical min,max angular deflection, to allow calibrating open-loop servo movements class RC_Channel_aux : public RC_Channel{ public: /// Constructor @@ -24,9 +23,7 @@ public: /// RC_Channel_aux(AP_Var::Key key, const prog_char_t *name) : RC_Channel(key, name), - function (&_group, 4, k_none, name ? PSTR("FUNCTION") : 0), // suppress name if group has no name - angle_min (&_group, 5, -4500, name ? PSTR("ANGLE_MIN") : 0), // assume -45 degrees min deflection - angle_max (&_group, 6, 4500, name ? PSTR("ANGLE_MAX") : 0) // assume 45 degrees max deflection + function (&_group, 4, k_none, name ? PSTR("FUNCTION") : 0) // suppress name if group has no name {} typedef enum @@ -41,8 +38,6 @@ public: } Aux_servo_function_t; AP_Int8 function; // 0=disabled, 1=manual, 2=flap, 3=flap auto, 4=aileron, 5=flaperon, 6=mount yaw (pan), 7=mount pitch (tilt), 8=mount roll, 9=camera trigger, 10=camera open, 11=egg drop - AP_Int16 angle_min; // min angle limit of actuated surface in 0.01 degree units - AP_Int16 angle_max; // max angle limit of actuated surface in 0.01 degree units void output_ch(unsigned char ch_nr); // map a function to a servo channel and output it