TradHeli: BugFix to ColYaw

Credit to Jolyon Saunders for finding this bug.
This commit is contained in:
Robert Lefebvre 2013-09-19 11:56:47 -04:00 committed by Randy Mackay
parent bba7fdc7c3
commit 9ac051c56d

View File

@ -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);
}
}