AP_MotorsHeli: Yaw servo to move when using SV_MAN param for setup.

This commit is contained in:
Robert Lefebvre 2015-10-21 10:15:42 -04:00 committed by Randy Mackay
parent c2dff8749e
commit 4443ca9602
1 changed files with 2 additions and 2 deletions

View File

@ -268,14 +268,14 @@ void AP_MotorsHeli::output_disarmed()
_roll_control_input = 0;
_pitch_control_input = 0;
_throttle_control_input = 1000;
_yaw_control_input = 0;
_yaw_control_input = 4500;
break;
case SERVO_CONTROL_MODE_MANUAL_MIN:
// fixate min collective
_roll_control_input = 0;
_pitch_control_input = 0;
_throttle_control_input = 0;
_yaw_control_input = 0;
_yaw_control_input = -4500;
break;
default:
// no manual override