From 2ba6e7af35b406292ff61a43a30d4e29de624330 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 18 Apr 2017 09:40:49 +1000 Subject: [PATCH] Copter: fixed aux servos in RC failsafe we should always output to channels --- ArduCopter/motors.cpp | 9 +++++++++ ArduCopter/radio.cpp | 3 --- 2 files changed, 9 insertions(+), 3 deletions(-) diff --git a/ArduCopter/motors.cpp b/ArduCopter/motors.cpp index bb3e9c2f18..9eb9ea474f 100644 --- a/ArduCopter/motors.cpp +++ b/ArduCopter/motors.cpp @@ -292,6 +292,12 @@ void Copter::motors_output() // output any servo channels SRV_Channels::calc_pwm(); + + // cork now, so that all channel outputs happen at once + hal.rcout->cork(); + + // update output on any aux channels, for manual passthru + SRV_Channels::output_ch_all(); // check if we are performing the motor test if (ap.motor_test) { @@ -309,6 +315,9 @@ void Copter::motors_output() // send output signals to motors motors->output(); } + + // push all channels + hal.rcout->push(); } // check for pilot stick input to trigger lost vehicle alarm diff --git a/ArduCopter/radio.cpp b/ArduCopter/radio.cpp index 1054e3b8d4..dcd467af8b 100644 --- a/ArduCopter/radio.cpp +++ b/ArduCopter/radio.cpp @@ -99,9 +99,6 @@ void Copter::read_radio() ap.rc_receiver_present = true; } - // update output on any aux channels, for manual passthru - SRV_Channels::output_ch_all(); - // pass pilot input through to motors (used to allow wiggling servos while disarmed on heli, single, coax copters) radio_passthrough_to_motors();