From 0228a99d4e1b3ce0a9598e3a8535ad419012cbdb Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Wed, 21 Oct 2015 10:15:42 -0400 Subject: [PATCH] AP_MotorsHeli: Yaw servo to move when using SV_MAN param for setup. --- libraries/AP_Motors/AP_MotorsHeli.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli.cpp b/libraries/AP_Motors/AP_MotorsHeli.cpp index 5bb4320ee1..c47a73ce0c 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli.cpp @@ -267,14 +267,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