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.
This commit is contained in:
Doug Weibel 2011-09-11 17:37:42 -06:00 committed by Amilcar Lucas
parent 816bd59af6
commit 5a14d546bb
1 changed files with 1 additions and 0 deletions

View File

@ -23,6 +23,7 @@ static void init_rc_in()
g.channel_throttle.dead_zone = 6; g.channel_throttle.dead_zone = 6;
//set auxiliary ranges //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)->set_range(0,100);
G_RC_AUX(k_flap_auto)->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_aileron)->set_angle(SERVO_MAX);