From 5087a4262d8da3fd6770e9b3174a8512247cdb91 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 28 Oct 2023 21:16:14 +0100 Subject: [PATCH] Plane: set_servos_idle: output left and right throttles --- ArduPlane/servos.cpp | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 86078bb082..85fe2689f3 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -371,7 +371,14 @@ void Plane::set_servos_idle(void) SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, servo_value); SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, servo_value); SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, servo_value); + + SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0); + SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, 0.0); + SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, 0.0); + SRV_Channels::set_output_to_trim(SRV_Channel::k_throttle); + SRV_Channels::set_output_to_trim(SRV_Channel::k_throttleLeft); + SRV_Channels::set_output_to_trim(SRV_Channel::k_throttleRight); }