From 5b2dcc3a0c35e1a1add68f37b46dcc9171a12119 Mon Sep 17 00:00:00 2001 From: Ferruccio Vicari Date: Sun, 1 Sep 2024 03:37:53 +0000 Subject: [PATCH] AP_Motors: fix DDVP tail servo initialization --- libraries/AP_Motors/AP_MotorsHeli_Single.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp index ad0e7fff83..24380cc315 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp @@ -220,6 +220,8 @@ void AP_MotorsHeli_Single::init_outputs() case TAIL_TYPE::DIRECTDRIVE_VARPITCH: case TAIL_TYPE::DIRECTDRIVE_VARPIT_EXT_GOV: _tail_rotor.init_servo(); + // yaw servo is an angle from -4500 to 4500 + SRV_Channels::set_angle(SRV_Channel::k_motor4, YAW_SERVO_MAX_ANGLE); break; case TAIL_TYPE::SERVO_EXTGYRO: