mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: fix DDVP tail servo initialization
This commit is contained in:
parent
ffadbc3a0c
commit
3e5dbb225a
|
@ -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:
|
||||
|
|
Loading…
Reference in New Issue