Browse Source

Plane: no need to set flaperons separately from flaperon_update()

fixes issue #1622

thanks to klrill-ka
mission-4.1.18
Andrew Tridgell 10 years ago
parent
commit
2bb7606fba
  1. 2
      ArduPlane/failsafe.pde

2
ArduPlane/failsafe.pde

@ -69,8 +69,6 @@ void failsafe_check(void) @@ -69,8 +69,6 @@ void failsafe_check(void)
RC_Channel_aux::set_servo_out(RC_Channel_aux::k_elevator, pitch);
RC_Channel_aux::set_servo_out(RC_Channel_aux::k_rudder, rudder);
RC_Channel_aux::set_servo_out(RC_Channel_aux::k_steering, rudder);
RC_Channel_aux::set_servo_out(RC_Channel_aux::k_flaperon1, roll);
RC_Channel_aux::set_servo_out(RC_Channel_aux::k_flaperon2, roll);
if (g.vtail_output != MIXING_DISABLED) {
channel_output_mixer(g.vtail_output, channel_pitch->radio_out, channel_rudder->radio_out);

Loading…
Cancel
Save