Browse Source

Plane: disable AUX passthrough during termination

mission-4.1.18
Andrew Tridgell 8 years ago
parent
commit
856b4f4d14
  1. 2
      ArduPlane/afs_plane.cpp

2
ArduPlane/afs_plane.cpp

@ -28,6 +28,8 @@ void AP_AdvancedFailsafe_Plane::terminate_vehicle(void) @@ -28,6 +28,8 @@ void AP_AdvancedFailsafe_Plane::terminate_vehicle(void)
ch_yaw->set_radio_out(ch_yaw->get_limit_pwm(RC_Channel::RC_CHANNEL_LIMIT_MAX));
ch_throttle->set_radio_out(ch_throttle->get_limit_pwm(RC_Channel::RC_CHANNEL_LIMIT_MIN));
RC_Channel_aux::disable_passthrough(true);
plane.servos_output();
// and all aux channels

Loading…
Cancel
Save