APM_Control: Simpify yaw controller trig

This commit is contained in:
Michael du Breuil 2017-09-24 17:06:51 -07:00 committed by Tom Pittenger
parent eb9dd8c5a2
commit c34104b369

View File

@ -102,7 +102,7 @@ int32_t AP_YawController::get_servo_out(float scaler, bool disable_integrator)
// If no airspeed available use average of min and max
aspeed = 0.5f*(float(aspd_min) + float(aparm.airspeed_max));
}
rate_offset = (GRAVITY_MSS / MAX(aspeed , float(aspd_min))) * tanf(bank_angle) * cosf(bank_angle) * _K_FF;
rate_offset = (GRAVITY_MSS / MAX(aspeed , float(aspd_min))) * sinf(bank_angle) * _K_FF;
// Get body rate vector (radians/sec)
float omega_z = _ahrs.get_gyro().z;