From f05f56f83f6e01855efef5baa59cf49b29b06258 Mon Sep 17 00:00:00 2001 From: Doug Weibel Date: Sun, 11 Sep 2011 17:37:42 -0600 Subject: [PATCH] Correct bug in initialization of auxiliary channels The value of aux_servo_function[CH_x] was not being set before the radio init_rc_in() function was setting channel angle/range. --- ArduPlane/radio.pde | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduPlane/radio.pde b/ArduPlane/radio.pde index ed3d1782b2..5b26479ce6 100644 --- a/ArduPlane/radio.pde +++ b/ArduPlane/radio.pde @@ -23,6 +23,7 @@ static void init_rc_in() g.channel_throttle.dead_zone = 6; //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);