Browse Source

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.
mission-4.1.18
Doug Weibel 14 years ago committed by Amilcar Lucas
parent
commit
f05f56f83f
  1. 1
      ArduPlane/radio.pde

1
ArduPlane/radio.pde

@ -23,6 +23,7 @@ static void init_rc_in() @@ -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);

Loading…
Cancel
Save