From 9ac051c56de606a254a0508d017979b5a191803c Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Thu, 19 Sep 2013 11:56:47 -0400 Subject: [PATCH] TradHeli: BugFix to ColYaw Credit to Jolyon Saunders for finding this bug. --- libraries/AP_Motors/AP_MotorsHeli.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli.cpp b/libraries/AP_Motors/AP_MotorsHeli.cpp index fc17685c8e..15ff27010f 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli.cpp @@ -581,7 +581,7 @@ void AP_MotorsHeli::move_swash(int16_t roll_out, int16_t pitch_out, int16_t coll // the feed-forward is not required when the motor is shut down and not creating torque // also not required if we are using external gyro if (motor_runup_complete() && _tail_type != AP_MOTORS_HELI_TAILTYPE_SERVO_EXTGYRO) { - yaw_offset = _collective_yaw_effect * abs(coll_out_scaled - _collective_mid_pwm); + yaw_offset = _collective_yaw_effect * abs(_collective_out - _collective_mid_pwm); } }