TradHeli: empty angle_boost for trad heli

This commit is contained in:
Randy Mackay 2014-01-31 09:59:50 +09:00 committed by Andrew Tridgell
parent 1648ecc6e5
commit a7504faa7d

View File

@ -281,14 +281,7 @@ float AC_AttitudeControl_Heli::rate_bf_to_motor_yaw(float rate_target_cds)
// throttle value should be 0 ~ 1000 // throttle value should be 0 ~ 1000
int16_t AC_AttitudeControl_Heli::get_angle_boost(int16_t throttle_pwm) int16_t AC_AttitudeControl_Heli::get_angle_boost(int16_t throttle_pwm)
{ {
float temp = _cos_pitch * _cos_roll; // no angle boost for trad helis
_angle_boost = 0;
temp = 1.0f - constrain_float(temp, 0.5f, 1.0f); return throttle_pwm;
int16_t throttle_above_mid = max(throttle_pwm - ((AP_MotorsHeli&)_motors).get_collective_mid(),0);
// to allow logging of angle boost
_angle_boost = throttle_above_mid*temp;
return throttle_pwm + _angle_boost;
} }