mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Motors: fix DDVP tail servo initialization
This commit is contained in:
parent
22caa52d58
commit
5b2dcc3a0c
@ -220,6 +220,8 @@ void AP_MotorsHeli_Single::init_outputs()
|
|||||||
case TAIL_TYPE::DIRECTDRIVE_VARPITCH:
|
case TAIL_TYPE::DIRECTDRIVE_VARPITCH:
|
||||||
case TAIL_TYPE::DIRECTDRIVE_VARPIT_EXT_GOV:
|
case TAIL_TYPE::DIRECTDRIVE_VARPIT_EXT_GOV:
|
||||||
_tail_rotor.init_servo();
|
_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;
|
break;
|
||||||
|
|
||||||
case TAIL_TYPE::SERVO_EXTGYRO:
|
case TAIL_TYPE::SERVO_EXTGYRO:
|
||||||
|
Loading…
Reference in New Issue
Block a user