TradHeli: COLYAW not applied when the motor is not running

This commit is contained in:
Robert Lefebvre 2013-07-23 15:16:14 -04:00 committed by Randy Mackay
parent 9ae66c1773
commit 4426060ccc

View File

@ -578,7 +578,9 @@ void AP_MotorsHeli::move_swash(int16_t roll_out, int16_t pitch_out, int16_t coll
coll_out_scaled = _collective_out * _collective_scalar + _collective_min - 1000;
// rudder feed forward based on collective
if (_tail_type != AP_MOTORS_HELI_TAILTYPE_SERVO_EXTGYRO) {
// 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);
}
}