AP_Motors: fix DDVP tail servo initialization

This commit is contained in:
Ferruccio Vicari 2024-09-01 03:37:53 +00:00 committed by Bill Geyer
parent 22caa52d58
commit 5b2dcc3a0c
1 changed files with 2 additions and 0 deletions

View File

@ -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: