VehicleDynamics.Wheels.MFTyre

VehicleDynamics.Wheels.MFTyre.TyreForces VehicleDynamics.Wheels.MFTyre.Wheel VehicleDynamics.Wheels.MFTyre.WheelWithForceAnimation VehicleDynamics.Wheels.MFTyre.TyreData VehicleDynamics.Wheels.MFTyre.MFpureSlip VehicleDynamics.Wheels.MFTyre.MFcombinedSlip VehicleDynamics.Wheels.MFTyre.MFcosine VehicleDynamics.Wheels.MFTyre.MFsine VehicleDynamics.Wheels.MFTyre.MFtransient

NameDescription
TyreForces Compute tyre forces and torques for steady state conditions
Wheel Wheel model according to the Magic formula
WheelWithForceAnimation Wheel model according to the Magic Formula, with animated tyre forces
TyreData Tyre data
MFpureSlip  
MFcombinedSlip  
MFcosine  
MFsine  
MFtransient  
TyreForceTest  


VehicleDynamics.Wheels.MFTyre.TyreForces VehicleDynamics.Wheels.MFTyre.TyreForces

Compute tyre forces and torques for steady state conditions

VehicleDynamics.Wheels.MFTyre.TyreForces

Parameters

NameDefaultDescription
transienttruetrue if transient behaviour should be considered.
combinedtruetrue if combined slip should be considered.
leftWheeltrueTRUE if tyre is mounted left.
radius00.3[m]
F_z03000nominal load
v_eps0.1[m/s]
data Data of tyre

Modelica definition

block TyreForces 
  "Compute tyre forces and torques for steady state conditions" 
  
  input SI.Velocity v_x "Contact point longitudinal speed";
  input SI.Velocity v_y "Contact point lateral speed";
  input Boolean contact "true if wheel has contact to ground";
  input SI.AngularVelocity w "Angular welocity of rim";
  input SI.Angle gamma "Camber angle";
  input SI.Force Fz "normal force";
  
  /*
  input SI.Angle alpha1 "slip angle";
  input Real kappa1 "kappa";
  input SI.Angle gamma1 "Camber angle";
  input SI.Force Fz "normal force";
*/
  output SI.Force Fx "Tyre force in x-direction";
  output SI.Force Fy "Tyre force in y-direction";
  output SI.Torque Mz "Tyre torque in z-direction";
  output SI.Position u "Longitudinal tyre deflection";
  output SI.Position v "Lateral tyre deflection";
  
  //  output SI.Force My 
  //    "Rolling resistance force for steady state conditions";
  
  /**************************************************************************/
  //USER PARAMETERS
  parameter Boolean transient=true 
    "true if transient behaviour should be considered.";
  parameter Boolean combined=true "true if combined slip should be considered.";
  parameter Boolean leftWheel=true "TRUE if tyre is mounted left.";
  
  parameter SI.Position radius0=0.3;
  
  constant Real pi=Modelica.Constants.PI;
  parameter Real F_z0=3000 "nominal load";
  parameter SI.Velocity v_eps=0.1;
  
  Real F_z=Fz;
  
  //SLIP DEFINITION
  SI.Velocity v_sx "Longitudinal slip speed";
  SI.Velocity v_xNonZero "Nonzero longitudinal speed";
  SI.Angle alpha1 
    "Angle between wheel axis velocity and the x-direction of the wheel";
  Real kappa1 "slip at contact point computed with contact velocities";
  SI.Angle ssAlpha 
    "Angle between wheel axis velocity and the x-direction of the wheel";
  Real ssKappa "slip at contact point computed with contact velocities";
  SI.Angle ttAlpha 
    "Angle between wheel axis velocity and the x-direction of the wheel";
  Real ttKappa "slip at contact point computed with contact velocities";
  
  //ROLLING RADIUS
  SI.Position rho "radial tyre deflection";
  SI.Position rho_0 "nominal tyre deflection";
  Real B_roll;
  Real D_roll;
  Real F_roll;
  Real R_e;
  
  /******************PURE SLIP***********************************************/
  //longitudinal
protected 
  Real p_Cx1 "shape factor C";
  Real p_Dx1 "peak factor D";
  Real p_Dx2 "peak factor D";
  Real p_Ex1 "curvature factor E";
  Real p_Ex2 "curvature factor E";
  Real p_Ex3 "curvature factor E";
  Real p_Ex4 "curvature factor E";
  Real p_Kx1 "slip stiffness BCD";
  Real p_Kx2 "slip stiffness BCD";
  Real p_Kx3 "slip stiffness BCD";
  Real p_Hx1 "horisontal shift H";
  Real p_Hx2 "horisontal shift H";
  Real p_Vx1 "vertical shift V";
  Real p_Vx2 "vertical shift V";
  //lateral
  Real p_Cy1 "shape factor C";
  Real p_Dy1 "peak factor D";
  Real p_Dy2 "peak factor D";
  Real p_Dy3 "peak factor D";
  Real p_Ey1 "curvature factor E";
  Real p_Ey2 "curvature factor E";
  Real p_Ey3 "curvature factor E";
  Real p_Ey4 "curvature factor E";
  Real p_Ky1 "slip stiffness BCD";
  Real p_Ky2 "slip stiffness BCD";
  Real p_Ky3 "slip stiffness BCD";
  Real p_Hy1 "horisontal shift H";
  Real p_Hy2 "horisontal shift H";
  Real p_Hy3 "horisontal shift H";
  Real p_Vy1 "vertical shift V";
  Real p_Vy2 "vertical shift V";
  Real p_Vy3 "vertical shift V";
  Real p_Vy4 "vertical shift V";
  //aligning torque
  Real q_Bz1 "stiffness factor B";
  Real q_Bz2 "stiffness factor B";
  Real q_Bz3 "stiffness factor B";
  Real q_Bz4 "stiffness factor B";
  Real q_Bz5 "stiffness factor B";
  Real q_Bz9 "stiffness factor B";
  Real q_Cz1 "shape factor C";
  Real q_Dz1 "peak factor D";
  Real q_Dz2 "peak factor D";
  Real q_Dz3 "peak factor D";
  Real q_Dz4 "peak factor D";
  Real q_Dz6 "peak factor D";
  Real q_Dz7 "peak factor D";
  Real q_Dz8 "peak factor D";
  Real q_Dz9 "peak factor D";
  Real q_Ez1 "curvature factor E";
  Real q_Ez2 "curvature factor E";
  Real q_Ez3 "curvature factor E";
  Real q_Ez4 "curvature factor E";
  Real q_Ez5 "curvature factor E";
  Real q_Hz1 "horisontal shift H";
  Real q_Hz2 "horisontal shift H";
  Real q_Hz3 "horisontal shift H";
  Real q_Hz4 "horisontal shift H";
  // User scaling Factors
  Real lambda_F_z0 "nominal load";
  Real lambda_muex "peak friction coefficient";
  Real lambda_muey "peak friction coefficient";
  Real lambda_Kx "slip stiffness";
  Real lambda_Ky "slip stiffness";
  Real lambda_Cx "shape factor";
  Real lambda_Cy "shape factor";
  Real lambda_Ex "curvature factor";
  Real lambda_Ey "curvature factor";
  Real lambda_Hx "horisontal shift";
  Real lambda_Hy "horisontal shift";
  Real lambda_Vx "vertical shift";
  Real lambda_Vy "vertical shift";
  Real lambda_gammay "camber force stiffness";
  Real lambda_gammaz "camber torque stiffness";
  Real lambda_t "pneumatic trail";
  Real lambda_r;
  Real lambda_Mr "residual torque";
  
  Real alpha_y;
  Real alpha_t;
  Real alpha_r;
  
  Real kappa_x;
  
  Real S_Vx;
  Real S_Hx;
  Real S_Hy;
  Real S_Vy;
  Real S_Ht;
  Real S_Hf;
  
  Real M_y;
  Real M_z;
  Real F_x;
  Real F_y;
  Real M_zr0;
  Real M_zr;
  Real F_y0;
  Real M_z0;
  Real F_x0;
  
  Real t;
  Real t_0;
  
  Real df_z;
  Real K_x;
  Real K_y;
  Real K_z;
  
  Real B_r;
  Real D_r;
  
  Real B_t;
  Real C_t;
  Real D_t;
  Real E_t;
  
  Real B_x;
  Real C_x;
  Real D_x;
  Real E_x;
  
  Real B_y;
  Real C_y;
  Real D_y;
  Real E_y;
  
  Real mue_x;
  Real mue_y;
  
  Real gamma_y;
  Real gamma_z;
  
  /**************** COMBINED SLIP ******************************************/
  
  //longitudinal
  SI.Position r_Bx1 "stiffness factor B";
  SI.Position r_Bx2 "stiffness factor B";
  SI.Position r_Cx1 "shape factor C";
  SI.Position r_Hx1 "horisontal shift H";
  
  //lateral slip
  SI.Position r_By1 "stiffness factor B";
  SI.Position r_By2 "stiffness factor B";
  SI.Position r_By3 "stiffness factor B";
  SI.Position r_Cy1 "shape factor C";
  SI.Position r_Hy1 "horisontal shift H";
  SI.Position r_Vy1 "vertical shift V";
  SI.Position r_Vy2 "vertical shift V";
  SI.Position r_Vy3 "vertical shift V";
  SI.Position r_Vy4 "vertical shift V";
  SI.Position r_Vy5 "vertical shift V";
  SI.Position r_Vy6 "vertical shift V";
  
  //aligning torque
  Real s_sz1;
  Real s_sz2;
  Real s_sz3;
  Real s_sz4;
  
  //user scaling factors
  Real lambda_xalpha;
  Real lambda_ykappa;
  Real lambda_Vykappa;
  Real lambda_s;
  
  Real B_xalpha;
  Real C_xalpha;
  Real S_Hxalpha;
  Real G_xalpha;
  
  Real B_ykappa;
  Real C_ykappa;
  Real S_Hykappa;
  Real S_Vykappa;
  Real D_Vykappa;
  Real G_ykappa;
  
  Real alpha_req;
  Real alpha_teq;
  Real s;
  
  /********TRANSIENT BEHAVIOUR********/
  
  Real p_Tx1;
  Real p_Tx2;
  Real p_Tx3;
  Real p_Ty1;
  Real p_Ty2;
  Real lambda_sigmaalpha;
  Real lambda_sigmakappa;
  
  Real sigma_kappa;
  Real sigma_alpha;
  
  Real zeta_x;
  Real zeta_y;
  
  SI.Velocity v_sy;
  SI.Velocity v_r;
  Real sign_v_r;
  Real abs_v_r;
  Real denNonZero;
  
protected 
  parameter Real left=if leftWheel then 1 else -1;
  Real gamma1=left*gamma;
  Real F_zNonZero;
public 
  parameter Wheels.RillTyre.TyreData data "Data of tyre";
  Wheels.MFTyre.MFpureSlip pureSlip;
  Wheels.MFTyre.MFsine longSlipPure;
  Wheels.MFTyre.MFsine latSlipPure;
  Wheels.MFTyre.MFcosine pneuTrail;
  Wheels.MFTyre.MFcosine resTorque;
  Wheels.MFTyre.MFcosine pneuTrail2;
  Wheels.MFTyre.MFcosine resTorque2;
  Wheels.MFTyre.MFcombinedSlip combinedSlip;
  MFtransient trans;
equation 
  /************EFFECTIVE ROLLING RADIUS, section 3.4**************/
  rho = Fz/data.c_z;
  rho_0 = F_z0/data.c_z;
  //R_e = data.R0;
  R_e = data.R0 - rho_0*(D_r*atan(B_r*rho/rho_0) + F_roll*rho/rho_0);
  B_roll = 8.4;
  D_roll = 0.27;
  F_roll = 0.045;
  F_zNonZero = if (F_z > 0 and contact) then F_z else v_eps;
  //if (contact) then F_z else v_eps;
  //Model cannot handle zero F_z
  
  /*******************SLIP DEFINITION*****************************/
  //-alpha1 = if (transient) then ttAlpha*left else ssAlpha*left;
  
  
    //kappa1 = if (ttKappa > 1) then 1 else if (ttKappa > -1) then ttKappa else -1;
  //kappa1 = if (transient) then ttKappa else ssKappa;
  kappa1 = -v_sx/(v_r*sign_v_r + 0.1);
  alpha1 = left*v_sy/(v_r*sign_v_r + 0.1);
  /*******************SLIP, TRANISENT, section 4.5****************/
  sigma_kappa*der(u) + abs_v_r*u = -sigma_kappa*v_sx;
  sigma_alpha*der(v) + abs_v_r*v = -sigma_alpha*v_sy;
  
  abs_v_r = v_r*sign_v_r + 0.1;
  sign_v_r = sign(v_r);
  
  ttAlpha = atan2(zeta_y, noEvent(abs(denNonZero)));
  ttKappa = zeta_x;
  // /(denNonZero);
  denNonZero = if ((abs(sign_v_r - zeta_x) > v_eps)) then sign_v_r - zeta_x
     else v_eps;
  
  zeta_x = if (noEvent(abs(sigma_kappa) > v_eps)) then u/sigma_kappa else u/
    v_eps;
  zeta_y = if (noEvent(abs(sigma_alpha) > v_eps)) then v/sigma_alpha else v/
    v_eps;
  
  sigma_alpha = p_Ty1*sin(2*atan(F_zNonZero/(p_Ty2*F_z0*lambda_F_z0)))*(1 - 
    p_Ky3*noEvent(abs(gamma1)))*data.R0*lambda_F_z0*lambda_sigmaalpha;
  sigma_kappa = F_zNonZero*(p_Tx1 + p_Tx2*df_z)*exp(-p_Tx3*df_z)*(data.R0/F_z0)
    *lambda_sigmakappa;
  
  trans.p_Tx1 = p_Tx1;
  trans.p_Tx2 = p_Tx2;
  trans.p_Tx3 = p_Tx3;
  trans.p_Ty1 = p_Ty1;
  trans.p_Ty2 = p_Ty2;
  trans.lambda_sigmaalpha = lambda_sigmaalpha;
  trans.lambda_sigmakappa = lambda_sigmakappa;
  
  //assumptions
  v_sy = v_y;
  
  v_r = R_e*w;
  //tangential speed
  
  when change(contact) then
    //Tyre looses contact to ground or gets contact to ground
    reinit(u, 0);
    reinit(v, 0);
  end when;
  
  /*******************SLIP, STEADY STATE, section 3.5*************/
  if (noEvent(abs(v_x) < 1)) then
    ssAlpha = Modelica.Math.atan2(v_y, noEvent(abs(v_xNonZero)));
    ssKappa = if (noEvent(abs(v_r) < v_eps)) then 0 else -v_sx/v_xNonZero;
    v_xNonZero = v_eps;
  else
    ssAlpha = Modelica.Math.atan2(v_y, noEvent(abs(v_x)));
    ssKappa = -v_sx/v_xNonZero;
    v_xNonZero = v_x;
  end if;
  /*
  if (noEvent(abs(v_x) > abs(v_r))) then
    ssAlpha = Modelica.Math.atan2(v_y, noEvent(abs(v_x)));
    ssKappa = -v_sx/v_x;
  elseif (noEvent(abs(v_r) > v_eps)) then
    ssAlpha = Modelica.Math.atan2(v_y, noEvent(abs(v_r)));
    ssKappa = -v_sx/v_r;
  else  
    ssAlpha = 0;
    ssKappa = -v_sx/v_eps;
  end if;
*/
  v_sx = v_x - v_r;
  //  v_xNonZero=0.1;//dummy
  
  /*******************READ TYRE DATA FOR PURE SLIP****************/
  //longitudinal
  pureSlip.p_Cx1 = p_Cx1;
  pureSlip.p_Dx1 = p_Dx1;
  pureSlip.p_Dx2 = p_Dx2;
  pureSlip.p_Ex1 = p_Ex1;
  pureSlip.p_Ex2 = p_Ex2;
  pureSlip.p_Ex3 = p_Ex3;
  pureSlip.p_Ex4 = p_Ex4;
  pureSlip.p_Kx1 = p_Kx1;
  pureSlip.p_Kx2 = p_Kx2;
  pureSlip.p_Kx3 = p_Kx3;
  pureSlip.p_Vx1 = p_Vx1;
  pureSlip.p_Vx2 = p_Vx2;
  pureSlip.p_Hx1 = p_Hx1;
  pureSlip.p_Hx2 = p_Hx2;
  //lateral
  pureSlip.p_Cy1 = p_Cy1;
  pureSlip.p_Dy1 = p_Dy1;
  pureSlip.p_Dy2 = p_Dy2;
  pureSlip.p_Dy3 = p_Dy3;
  pureSlip.p_Ey1 = p_Ey1;
  pureSlip.p_Ey2 = p_Ey2;
  pureSlip.p_Ey3 = p_Ey3;
  pureSlip.p_Ey4 = p_Ey4;
  pureSlip.p_Ky1 = p_Ky1;
  pureSlip.p_Ky2 = p_Ky2;
  pureSlip.p_Ky3 = p_Ky3;
  pureSlip.p_Hy1 = p_Hy1;
  pureSlip.p_Hy2 = p_Hy2;
  pureSlip.p_Hy3 = p_Hy3;
  pureSlip.p_Vy1 = p_Vy1;
  pureSlip.p_Vy2 = p_Vy2;
  pureSlip.p_Vy3 = p_Vy3;
  pureSlip.p_Vy4 = p_Vy4;
  
  //aligning torque
  pureSlip.q_Bz1 = q_Bz1;
  pureSlip.q_Bz2 = q_Bz2;
  pureSlip.q_Bz3 = q_Bz3;
  pureSlip.q_Bz4 = q_Bz4;
  pureSlip.q_Bz5 = q_Bz5;
  pureSlip.q_Bz9 = q_Bz9;
  pureSlip.q_Cz1 = q_Cz1;
  pureSlip.q_Dz1 = q_Dz1;
  pureSlip.q_Dz2 = q_Dz2;
  pureSlip.q_Dz3 = q_Dz3;
  pureSlip.q_Dz4 = q_Dz4;
  pureSlip.q_Dz6 = q_Dz6;
  pureSlip.q_Dz7 = q_Dz7;
  pureSlip.q_Dz8 = q_Dz8;
  pureSlip.q_Dz9 = q_Dz9;
  pureSlip.q_Ez1 = q_Ez1;
  pureSlip.q_Ez2 = q_Ez2;
  pureSlip.q_Ez3 = q_Ez3;
  pureSlip.q_Ez4 = q_Ez4;
  pureSlip.q_Ez5 = q_Ez5;
  pureSlip.q_Hz1 = q_Hz1;
  pureSlip.q_Hz2 = q_Hz2;
  pureSlip.q_Hz3 = q_Hz3;
  pureSlip.q_Hz4 = q_Hz4;
  
  //user scaling factors
  pureSlip.lambda_F_z0 = lambda_F_z0;
  pureSlip.lambda_muex = lambda_muex;
  pureSlip.lambda_muey = lambda_muey;
  pureSlip.lambda_Kx = lambda_Kx;
  pureSlip.lambda_Ky = lambda_Ky;
  pureSlip.lambda_Cx = lambda_Cx;
  pureSlip.lambda_Cy = lambda_Cy;
  pureSlip.lambda_Ex = lambda_Ex;
  pureSlip.lambda_Ey = lambda_Ey;
  pureSlip.lambda_Hx = lambda_Hx;
  pureSlip.lambda_Hy = lambda_Hy;
  pureSlip.lambda_Vx = lambda_Vx;
  pureSlip.lambda_Vy = lambda_Vy;
  pureSlip.lambda_gammay = lambda_gammay;
  pureSlip.lambda_gammaz = lambda_gammaz;
  pureSlip.lambda_t = lambda_t;
  pureSlip.lambda_r = lambda_r;
  pureSlip.lambda_Mr = lambda_Mr;
  /********************************************************/
  
  df_z = F_zNonZero*(1 - lambda_F_z0)/lambda_F_z0;
  
  // pure longitudinal slip 
  kappa_x = kappa1 + S_Hx;
  M_y = (S_Vx + K_x*S_Hx);
  C_x = p_Cx1*lambda_Cx;
  D_x = mue_x*F_zNonZero;
  mue_x = (p_Dx1 + p_Dx2*df_z)*lambda_muex;
  E_x = (p_Ex1 + p_Ex2*df_z + p_Ex3*df_z*df_z)*(1 - p_Ex4*sign(kappa_x))*
    lambda_Ex;
  K_x = F_zNonZero*(p_Kx1 + p_Kx2*df_z)*Modelica.Math.exp(-p_Kx3*df_z)*
    lambda_Kx;
  B_x = noEvent(if abs(D_x*C_x) > 0 then K_x/(C_x*D_x) else 0);
  //C_x*D_x*B_x = K_x;
  //B_x = if D_x*C_x>0 then K_x/(C_x*D_x) else 0;
  S_Hx = (p_Hx1 + p_Hx2*df_z)*lambda_Hx;
  S_Vx = F_zNonZero*(p_Vx1 + p_Vx2*df_z)*lambda_Vx*lambda_muex;
  longSlipPure.x = kappa_x;
  longSlipPure.B = B_x;
  longSlipPure.C = C_x;
  longSlipPure.D = D_x;
  longSlipPure.E = E_x;
  longSlipPure.y + S_Vx = F_x0;
  
  // pure lateral slip 
  alpha_y = alpha1 + S_Hy;
  gamma_y = gamma1*lambda_gammay;
  
  C_y = p_Cy1*lambda_Cy;
  D_y = mue_y*F_zNonZero;
  mue_y = (p_Dy1 + p_Dy2*df_z)*(1 - p_Dy3*gamma_y*gamma_y)*lambda_muey;
  E_y = (p_Ey1 + p_Ey2*df_z)*(1 - (p_Ey3 + p_Ey4*gamma_y)*noEvent(if alpha_y < 
    0 then -1 else 1))*lambda_Ey;
  K_y = p_Ky1*F_z0*Modelica.Math.sin(2*Modelica.Math.atan(F_zNonZero/(p_Ky2*
    F_z0*lambda_F_z0)))*(1 - p_Ky3*noEvent(abs(gamma_y)))*lambda_F_z0*lambda_Ky;
  //consider algortihm
  //  B_y = K_y/(C_y*D_y);
  B_y = noEvent(if abs(D_y*C_y) > 0 then K_y/(C_y*D_y) else 0);
  //C_y*D_y*B_y = K_y;
  S_Hy = (p_Hy1 + p_Hy2*df_z + p_Hy3*gamma_y)*lambda_Hy;
  S_Vy = F_zNonZero*(p_Vy1 + p_Vy2*df_z + (p_Vy3 + p_Vy4*df_z)*gamma_y)*
    lambda_Vy*lambda_muey;
  
  latSlipPure.x = alpha_y;
  latSlipPure.B = B_y;
  latSlipPure.C = C_y;
  latSlipPure.D = D_y;
  latSlipPure.E = E_y;
  F_y0 = latSlipPure.y + S_Vy;
  
  //aligning torque
  M_z0 = -t*F_y0 + M_zr;
  t_0 = pneuTrail.y*Modelica.Math.cos(alpha1);
  pneuTrail.B = B_t;
  pneuTrail.C = C_t;
  pneuTrail.D = D_t;
  pneuTrail.E = E_t;
  pneuTrail.x = alpha_t;
  alpha_t = alpha1 + S_Ht;
  
  M_zr0 = resTorque.y*Modelica.Math.cos(alpha1);
  resTorque.B = B_r;
  resTorque.C = 1;
  resTorque.D = D_r;
  resTorque.E = 0;
  resTorque.x = alpha_r;
  alpha_r = alpha1 + S_Hf;
  
  S_Hf = (S_Hy + noEvent(if abs(K_y) > 0 then S_Vy/K_y else 0));
  gamma_z = gamma1*lambda_gammaz;
  B_t = (q_Bz1 + q_Bz2*df_z + q_Bz3*df_z*df_z)*(1 + q_Bz4*gamma_z + q_Bz5*
    noEvent(abs(gamma_z)))*lambda_Ky/lambda_muey;
  C_t = q_Cz1;
  D_t = F_zNonZero*(q_Dz1 + q_Dz2*df_z)*(1 + q_Dz3*gamma_z + q_Dz4*gamma_z*
    gamma_z)*(radius0/F_z0)*lambda_t;
  E_t = (q_Ez1*q_Ez2*df_z + q_Ez3*gamma_z*gamma_z)*(1 + (q_Ez4 + q_Ez5*gamma_z)
    *(2/pi)*Modelica.Math.atan(B_t*C_t*alpha_t));
  S_Ht = (q_Hz1 + q_Hz2*df_z + (q_Hz3*q_Hz4*df_z)*gamma_z);
  B_r = q_Bz9*lambda_Ky/lambda_muey;
  D_r = F_zNonZero*(q_Dz6 + q_Dz7*df_z + (q_Dz8 + q_Dz9*df_z)*gamma_z)*radius0*
    lambda_r*lambda_muey;
  K_z = t_0*K_y;
  
  //longitudinal slip
  combinedSlip.r_Bx1 = r_Bx1;
  combinedSlip.r_Bx2 = r_Bx2;
  combinedSlip.r_Cx1 = r_Cx1;
  combinedSlip.r_Hx1 = r_Hx1;
  
  //lateral slip
  combinedSlip.r_By1 = r_By1;
  combinedSlip.r_By2 = r_By2;
  combinedSlip.r_By3 = r_By3;
  combinedSlip.r_Cy1 = r_Cy1;
  combinedSlip.r_Hy1 = r_Hy1;
  combinedSlip.r_Vy1 = r_Vy1;
  combinedSlip.r_Vy2 = r_Vy2;
  combinedSlip.r_Vy3 = r_Vy3;
  combinedSlip.r_Vy4 = r_Vy4;
  combinedSlip.r_Vy5 = r_Vy5;
  combinedSlip.r_Vy6 = r_Vy6;
  
  //aligning torque
  combinedSlip.s_sz1 = s_sz1;
  combinedSlip.s_sz2 = s_sz2;
  combinedSlip.s_sz3 = s_sz3;
  combinedSlip.s_sz4 = s_sz4;
  
  //user scaling data
  combinedSlip.lambda_xalpha = lambda_xalpha;
  combinedSlip.lambda_ykappa = lambda_ykappa;
  combinedSlip.lambda_Vykappa = lambda_Vykappa;
  combinedSlip.lambda_s = lambda_s;
  
  //longitudinal slip
  B_xalpha = r_Bx1*Modelica.Math.cos(Modelica.Math.atan(r_Bx2*lambda_xalpha))*
    lambda_xalpha;
  C_xalpha = r_Cx1;
  S_Hxalpha = r_Hx1;
  
  G_xalpha = Modelica.Math.cos(C_xalpha*Modelica.Math.atan(B_xalpha*(alpha1 + 
    S_Hxalpha)))/Modelica.Math.cos(C_xalpha*Modelica.Math.atan(B_xalpha*
    S_Hxalpha));
  
  F_x = if (combined) then F_x0*G_xalpha else F_x0;
  
  //lateral slip
  B_ykappa = r_By1*Modelica.Math.cos(Modelica.Math.atan(r_By2*(alpha1 - r_By3)))
    *lambda_ykappa;
  C_ykappa = r_Cy1;
  S_Hykappa = r_Hy1;
  S_Vykappa = D_Vykappa*Modelica.Math.sin(r_Vy5*Modelica.Math.atan(r_Vy6*kappa1))
    *lambda_Vykappa;
  D_Vykappa = mue_y*F_zNonZero*(r_Vy1*r_Vy2*df_z + r_Vy3*gamma1)*
    Modelica.Math.cos(Modelica.Math.atan(r_Vy4*alpha1));
  G_ykappa = Modelica.Math.cos(C_ykappa*Modelica.Math.atan(B_ykappa*(kappa1 + 
    S_Hykappa)))/Modelica.Math.cos(C_ykappa*Modelica.Math.atan(B_ykappa*
    S_Hykappa));
  
  F_y = if (combined) then F_y0*G_ykappa + S_Vykappa else F_y0;
  
  //aligning torque
  
  t = pneuTrail2.y*Modelica.Math.cos(alpha1);
  pneuTrail2.B = B_t;
  pneuTrail2.C = C_t;
  pneuTrail2.D = D_t;
  pneuTrail2.E = E_t;
  pneuTrail2.x = alpha_teq;
  alpha_teq = Modelica.Math.atan(sqrt(Modelica.Math.tan(alpha_t)*
    Modelica.Math.tan(alpha_t) + (K_x*K_x/(K_y*K_y))))*sign(alpha_t);
  
  M_zr = resTorque2.y*Modelica.Math.cos(alpha1);
  resTorque2.B = B_r;
  resTorque2.C = 1;
  resTorque2.D = D_r;
  resTorque2.E = 0;
  resTorque2.x = alpha_req;
  alpha_req = Modelica.Math.atan(sqrt(Modelica.Math.tan(alpha_r)*
    Modelica.Math.tan(alpha_r) + (K_x*K_x/(K_y*K_y))))*sign(alpha_r);
  
  s = (s_sz1 + s_sz2*(F_y/F_z0) + (s_sz3 + s_sz4*df_z)*gamma1)*radius0*lambda_s;
  
  //should be modifyed so that parts can be shut of  
  M_z = -t*(F_y - S_Vykappa) + s*F_x;
  //+ M_zgyr;
  
  /******************OUTPUT VARIABLES*****************************************/
  Fx = if not contact then 0 else if (noEvent(abs(v_r)) > v_eps) then F_x else 
    0;
  Fy = if contact then F_y*left else 0;
  Mz = if contact then M_z*left else 0;
  
  /**************************************************************************/
  
end TyreForces;

VehicleDynamics.Wheels.MFTyre.Wheel VehicleDynamics.Wheels.MFTyre.Wheel

Wheel model according to the Magic formula

VehicleDynamics.Wheels.MFTyre.Wheel

Information

This element contains the inertia properties of a
rotating wheel and the tyre forces acting at the
contact point of the wheel with the road. The tyre forces
are computed accorded to the equations of Rill (see reference below).
The wheel data is defined via the record WheelData and the tire
data is defined via the record RillTyre.TyreData.
Therefore, it suffices to define one instance of
these records and use them for all 4 wheels of a vehicle.
The frames of this object have the following meaning:
Frame carrierFrame is fixed in the carrier of the wheel
and is located on the spin axis of the wheel in the
middle point of the wheel. This point is also approximately
used as the center-of-mass of the wheel.
It is temporarily assumed that the road lies in the
x-y plane of the inertial frame! This restriction can
be removed by defining the road properties via inner/outer
functions.
Flange driveShaft is used to drive the wheel with
a 1D-drive train.
This element is realized according to the description
  Georg Rill: Simulation von Kraftfahrzeugen,
              Vieweg, 1994

Parameters

NameDefaultDescription
n[3]{0,1,0}Unit vector in direction of spin axis (same direction for left and right wheel)
leftWheeltruetrue, if left wheel, otherwise right wheel
exactfalsefalse if influence of bearing acceleration is neglected

Modelica definition

model Wheel "Wheel model according to the Magic formula" 
  
  import Car;
  import Modelica.Math;
  extends Utilities.BaseWheel(final wheelData(
      R0=tyreData.R0, 
      width=tyreData.width, 
      m=tyreData.m, 
      Iyy=tyreData.Iyy, 
      Ixx=tyreData.Ixx));
  
  //USER PARAMETERS
  Boolean transient=true "true if transient behaviour should be considered.";
  Boolean combined=true "true if combined slip should be considered.";
  
  //TYRE CONTACT 
  Boolean contact "true, if wheel has contact with road";
  SI.Position delta_z "vertical deflection of tyre";
  
  //FORCE GENERATION
  SI.Force f_x "Tyre/contact force at origin of W-frame in x-direction";
  SI.Force f_y "Tyre/contact force at origin of W-frame in y-direction";
  SI.Force f_z "Tyre/contact force at origin of W-frame in z-direction";
  SI.Force t_z "Tyre/contact torque at origin of W-frame in z-direction";
  
  //VISUAL REPRESENTATION
  Real S_rel[3, 3];
  
protected 
  parameter Real left=if (leftWheel) then 1 else -1;
public 
  Wheels.RillTyre.TyreData tyreData;
  
  VisualShape shape_1(
    r0=-nShape*0.7*abs(wheelData.width), 
    Length=abs(wheelData.width), 
    Width=2*wheelData.R0, 
    Height=2*wheelData.R0, 
    LengthDirection=nShape, 
    WidthDirection={1,0,0}, 
    Shape="pipe", 
    Material={0,0,0,.3}, 
    Extra=0.7);
  VisualShape shape0(
    r0=abs(wheelData.width)*nShape*0.2, 
    Length=wheelData.R0 - 0.01, 
    Width=0.02, 
    Height=0.05, 
    WidthDirection=-nShape, 
    Material={0.2,0,0,0.7});
  VisualShape shape1(
    r0=abs(wheelData.width)*nShape*0.2, 
    Length=wheelData.R0 - 0.01, 
    Width=0.02, 
    Height=0.05, 
    LengthDirection={0.6235,0,0.7818}, 
    WidthDirection=-nShape, 
    Material={0.2,0.2,0.2,0.7});
  VisualShape shape2(
    r0=abs(wheelData.width)*nShape*0.2, 
    Length=wheelData.R0 - 0.01, 
    Width=0.02, 
    Height=0.05, 
    LengthDirection={-0.2225,0,0.9749}, 
    WidthDirection=-nShape, 
    Material={0.2,0.2,0.2,0.7});
  VisualShape shape3(
    r0=abs(wheelData.width)*nShape*0.2, 
    Length=wheelData.R0 - 0.01, 
    Width=0.02, 
    Height=0.05, 
    LengthDirection={-0.9010,0,0.4339}, 
    WidthDirection=-nShape, 
    Material={0.2,0.2,0.2,0.7});
  VisualShape shape4(
    r0=abs(wheelData.width)*nShape*0.2, 
    Length=wheelData.R0 - 0.01, 
    Width=0.02, 
    Height=0.05, 
    LengthDirection={-0.9010,0,-0.4339}, 
    WidthDirection=-nShape, 
    Material={0.2,0.2,0.2,0.7});
  VisualShape shape5(
    r0=abs(wheelData.width)*nShape*0.2, 
    Length=wheelData.R0 - 0.01, 
    Width=0.02, 
    Height=0.05, 
    LengthDirection={-0.2225,0,-0.9749}, 
    WidthDirection=-nShape, 
    Material={0.2,0.2,0.2,0.7});
  VisualShape shape6(
    r0=abs(wheelData.width)*nShape*0.2, 
    Length=wheelData.R0 - 0.01, 
    Width=0.02, 
    Height=0.05, 
    LengthDirection={0.6235,0,-0.7818}, 
    WidthDirection=-nShape, 
    Material={0.2,0.2,0.2,0.7});
  Wheels.MFTyre.TyreForces tyreForces(
    leftWheel=leftWheel, 
    radius0=tyreData.R0, 
    data=tyreData);
equation 
  
  //NORMAL FORCE
  //according to Rill:
  delta_z = if delta_r >= 0 then delta_r else 0;
  contact = delta_r >= 0;
  //end when;
  // Compute  force perpendicular to contact plane.
  f_z = if (delta_r >= 0 and tyreData.c_z*delta_z + tyreData.d_z*ddelta_r > 0)
     then tyreData.c_z*delta_z + tyreData.d_z*ddelta_r else 0;
  
  //TYRE FORCE GENERATION
  tyreForces.v_x = v_x;
  tyreForces.v_y = v_y;
  tyreForces.w = w;
  tyreForces.contact = contact;
  tyreForces.gamma1 = camberAngle;
  tyreForces.Fz = f_z;
  
  tyreForces.Fx = f_x;
  tyreForces.Fy = f_y;
  tyreForces.Mz = t_z;
  
  //FORCES AND MOMENTS REQUIRED BY THE BaseWheel
  F_x = f_x;
  F_y = f_y;
  F_z = f_z;
  M_x = 0;
  //this model is yet unable to generate overturning moment 
  M_y = 0;
  //and roll resistance torque.
  M_z = t_z;
  
  //VISUAL REPRESENTATION OF TYRE AND RIM
  S_rel = [nn]*transpose([nn]) + (identity(3) - [nn]*transpose([nn]))*cos(phi)
     - skew(nn)*sin(phi);
  //tyre
  shape_1.S = wheel_body.frame_b.S*transpose(S_rel);
  shape_1.r = wheel_body.frame_b.r0;
  //rim
  shape0.S = shape_1.S;
  shape0.r = shape_1.r;
  shape1.S = shape0.S;
  shape1.r = shape0.r;
  shape2.S = shape1.S;
  shape2.r = shape1.r;
  shape3.S = shape2.S;
  shape3.r = shape2.r;
  shape4.S = shape3.S;
  shape4.r = shape3.r;
  shape5.S = shape4.S;
  shape5.r = shape4.r;
  shape6.S = shape5.S;
  shape6.r = shape5.r;
  
end Wheel;

VehicleDynamics.Wheels.MFTyre.WheelWithForceAnimation VehicleDynamics.Wheels.MFTyre.WheelWithForceAnimation

Wheel model according to the Magic Formula, with animated tyre forces

VehicleDynamics.Wheels.MFTyre.WheelWithForceAnimation

Parameters

NameDefaultDescription
n[3]{0,1,0}Unit vector in direction of spin axis (same direction for left and right wheel)
leftWheeltruetrue, if left wheel, otherwise right wheel
exactfalsefalse if influence of bearing acceleration is neglected
wheelDatafinal wheelData(R0=tyreData.R0, width=tyreData.width, m=tyreData.m, Iyy=tyreData.Iyy, Ixx=tyreData.Ixx) 
scale_F_x1scaling of visual appearance of F_x
scale_F_y1scaling of visual appearance of F_y
scale_F_z1/tyreData.load1.Fz_nomscaling of visual appearance of F_z
scale_M_z1scaling of visual appearance of M_z

Modelica definition

model WheelWithForceAnimation 
  "Wheel model according to the Magic Formula, with animated tyre forces"
   
  
  extends Wheel;
  parameter Real scale_F_x=1 "scaling of visual appearance of F_x";
  parameter Real scale_F_y=1 "scaling of visual appearance of F_y";
  parameter Real scale_F_z=1/tyreData.load1.Fz_nom 
    "scaling of visual appearance of F_z";
  parameter Real scale_M_z=1 "scaling of visual appearance of M_z";
  VisualVector force_x(
    category="force", 
    r=Wr, 
    Size=We_x*(scale_F_x*F_x), 
    S=Sroad);
  VisualVector force_y(
    Material={0,1,0,0.5}, 
    category="force", 
    r=Wr, 
    Size=We_y*(scale_F_y*F_y), 
    S=Sroad);
  VisualVector force_z(
    Material={0,0,1,0.5}, 
    category="force", 
    r=Wr, 
    Size=We_z*(scale_F_z*F_z), 
    S=Sroad);
  VisualVector torque(
    Material={1,0,0,0.5}, 
    category="torque", 
    r=Wr, 
    Size=Wt*scale_M_z*M_z, 
    S=Sroad);
end WheelWithForceAnimation;

VehicleDynamics.Wheels.MFTyre.TyreData VehicleDynamics.Wheels.MFTyre.TyreData

Tyre data

Parameters

NameDefaultDescription
R00.3undeformed radius of wheel [m]
Rrim0.2radius of rim [m]
width0.19width of wheel (>0) [m]
m10mass of wheel [kg]
Iyy1wheel inertia with respect to wheel axis [kg.m2]
Ixx1wheel inertia with respect to axis perpendicular to wheel axis [kg.m2]
lambda_muey1 
c_x100000tyre spring constant in x-direction [N/m]
c_y150000tyre spring constant in y-direction [N/m]
c_z200000tyre spring constant in z-direction [N/m]
d_x1500tyre damping constant in x-direction [N.s/m]
d_y300tyre damping constant in y-direction [N.s/m]
d_z300tyre damping constant in z-direction [N.s/m]
mue_nom0.7friction coefficient of road for which tyre data is valid

Modelica definition

record TyreData "Tyre data" 
  extends Wheels.Utilities.WheelData;
  
  parameter Real lambda_muey=1;
  // Spring and damping characteristic of tyre
  parameter Real c_x(unit="N/m") = 100000 "tyre spring constant in x-direction";
  parameter Real c_y(unit="N/m") = 150000 "tyre spring constant in y-direction";
  parameter Real c_z(unit="N/m") = 200000 "tyre spring constant in z-direction";
  parameter Real d_x(unit="N.s/m") = 1500 
    "tyre damping constant in x-direction";
  parameter Real d_y(unit="N.s/m") = 300 "tyre damping constant in y-direction";
  parameter Real d_z(unit="N.s/m") = 300 "tyre damping constant in z-direction";
  
  // Data for nominal vertical load 1
  parameter Real mue_nom=0.7 
    "friction coefficient of road for which tyre data is valid";
  
  Wheels.RillTyre.NominalLoad load1(F_max_y=lambda_muey);
  Wheels.RillTyre.NominalLoad load2(
    Fz_nom=6000, 
    Fds_x=75000, 
    s_max_x=0.18, 
    F_max_x=4500, 
    s_slide_x=0.5, 
    F_slide_x=4200, 
    Fds_y=60000, 
    s_max_y=0.24, 
    F_max_y=4125*lambda_muey, 
    s_slide_y=0.8, 
    F_slide_y=3750, 
    dL0=0.1, 
    s0=0.275, 
    sE=0.8);
end TyreData;

VehicleDynamics.Wheels.MFTyre.MFpureSlip VehicleDynamics.Wheels.MFTyre.MFpureSlip

Parameters

NameDefaultDescription
p_Cx11.75757shape factor C
p_Dx11.08851peak factor D
p_Dx2-0.0312973peak factor D
p_Ex10.551769curvature factor E
p_Ex2-0.049158 
p_Ex30.05 
p_Ex40curvature factor E
p_Kx119.0610slip stiffness BCD
p_Kx20.0017 
p_Kx30.483251slip stiffness BCD
p_Hx1-.000545*0horisontal shift H
p_Hx20*0.000209horisontal shift H
p_Vx10vertical shift V
p_Vx20vertical shift V
p_Cy11.20328shape factor C
p_Dy1-1.07146peak factor D
p_Dy20.178566peak factor D
p_Dy32.78722peak factor D
p_Ey1-1.56726curvature factor E
p_Ey2-.548012curvature factor E
p_Ey3-.188264curvature factor E
p_Ey45.14031curvature factor E
p_Ky1-15.9592slip stiffness BCD
p_Ky21.161200slip stiffness BCD
p_Ky30.623354slip stiffness BCD
p_Hy1-0.00716805horisontal shift H
p_Hy20.00319597horisontal shift H
p_Hy3-0.0994834horisontal shift H
p_Vy1-0.0122314vertical shift V
p_Vy2-0.000606665vertical shift V
p_Vy3-0.753073vertical shift V
p_Vy40.558202vertical shift V
q_Bz110.7807stiffness factor B
q_Bz2-4.0056stiffness factor B
q_Bz31.84837stiffness factor B
q_Bz40.294563stiffness factor B
q_Bz50stiffness factor B
q_Bz931.8193stiffness factor B
q_Cz11.23342shape factor C
q_Dz10.0916462peak factor D
q_Dz20.00317208peak factor D
q_Dz3-0.458539peak factor D
q_Dz40peak factor D
q_Dz60.00559840peak factor D
q_Dz7-0.00915360peak factor D
q_Dz80.332951peak factor D
q_Dz9-0.174946peak factor D
q_Ez1-2.51151curvature factor E
q_Ez21.14149curvature factor E
q_Ez30curvature factor E
q_Ez4-0.474070curvature factor E
q_Ez5-3.88634curvature factor E
q_Hz1-0.00397677horisontal shift H
q_Hz2-0.0036033horisontal shift H
q_Hz3-0.215809horisontal shift H
q_Hz4-0.168349horisontal shift H
lambda_F_z01nominal load
lambda_muex1peak friction coefficient
lambda_muey1peak friction coefficient
lambda_Kx1slip stiffness
lambda_Ky1slip stiffness
lambda_Cx1shape factor
lambda_Cy1shape factor
lambda_Ex1curvature factor
lambda_Ey1curvature factor
lambda_Hx1horisontal shift
lambda_Hy1horisontal shift
lambda_Vx1vertical shift
lambda_Vy1vertical shift
lambda_gammay1camber force stiffness
lambda_gammaz1camber torque stiffness
lambda_t1pneumatic trail
lambda_r1 
lambda_Mr1residual torque

Modelica definition

record MFpureSlip 
  //longitudinal
  parameter Real p_Cx1=1.75757 "shape factor C";
  parameter Real p_Dx1=1.08851 "peak factor D";
  parameter Real p_Dx2=-0.0312973 "peak factor D";
  parameter Real p_Ex1=0.551769 "curvature factor E";
  parameter Real p_Ex2=-0.049158;
  //0.370176 "curvature factor E";
  parameter Real p_Ex3=0.05;
  //-0.17014 "curvature factor E";
  parameter Real p_Ex4=0 "curvature factor E";
  parameter Real p_Kx1=19.0610 "slip stiffness BCD";
  parameter Real p_Kx2=0.0017;
  //-0.466168 "slip stiffness BCD";
  parameter Real p_Kx3=0.483251 "slip stiffness BCD";
  parameter Real p_Hx1=-.000545*0 "horisontal shift H";
  parameter Real p_Hx2=0*0.000209 "horisontal shift H";
  parameter Real p_Vx1=0 "vertical shift V";
  parameter Real p_Vx2=0 "vertical shift V";
  //lateral
  parameter Real p_Cy1=1.20328 "shape factor C";
  parameter Real p_Dy1=-1.07146 "peak factor D";
  parameter Real p_Dy2=0.178566 "peak factor D";
  parameter Real p_Dy3=2.78722 "peak factor D";
  parameter Real p_Ey1=-1.56726 "curvature factor E";
  parameter Real p_Ey2=-.548012 "curvature factor E";
  parameter Real p_Ey3=-.188264 "curvature factor E";
  parameter Real p_Ey4=5.14031 "curvature factor E";
  parameter Real p_Ky1=-15.9592 "slip stiffness BCD";
  parameter Real p_Ky2=1.161200 "slip stiffness BCD";
  parameter Real p_Ky3=0.623354 "slip stiffness BCD";
  parameter Real p_Hy1=-0.00716805 "horisontal shift H";
  parameter Real p_Hy2=0.00319597 "horisontal shift H";
  parameter Real p_Hy3=-0.0994834 "horisontal shift H";
  parameter Real p_Vy1=-0.0122314 "vertical shift V";
  parameter Real p_Vy2=-0.000606665 "vertical shift V";
  parameter Real p_Vy3=-0.753073 "vertical shift V";
  parameter Real p_Vy4=0.558202 "vertical shift V";
  //aligning torque
  parameter Real q_Bz1=10.7807 "stiffness factor B";
  parameter Real q_Bz2=-4.0056 "stiffness factor B";
  parameter Real q_Bz3=1.84837 "stiffness factor B";
  parameter Real q_Bz4=0.294563 "stiffness factor B";
  parameter Real q_Bz5=0 "stiffness factor B";
  parameter Real q_Bz9=31.8193 "stiffness factor B";
  parameter Real q_Cz1=1.23342 "shape factor C";
  parameter Real q_Dz1=0.0916462 "peak factor D";
  parameter Real q_Dz2=0.00317208 "peak factor D";
  parameter Real q_Dz3=-0.458539 "peak factor D";
  parameter Real q_Dz4=0 "peak factor D";
  parameter Real q_Dz6=0.00559840 "peak factor D";
  parameter Real q_Dz7=-0.00915360 "peak factor D";
  parameter Real q_Dz8=0.332951 "peak factor D";
  parameter Real q_Dz9=-0.174946 "peak factor D";
  parameter Real q_Ez1=-2.51151 "curvature factor E";
  parameter Real q_Ez2=1.14149 "curvature factor E";
  parameter Real q_Ez3=0 "curvature factor E";
  parameter Real q_Ez4=-0.474070 "curvature factor E";
  parameter Real q_Ez5=-3.88634 "curvature factor E";
  parameter Real q_Hz1=-0.00397677 "horisontal shift H";
  parameter Real q_Hz2=-0.0036033 "horisontal shift H";
  parameter Real q_Hz3=-0.215809 "horisontal shift H";
  parameter Real q_Hz4=-0.168349 "horisontal shift H";
  // User scaling Factors
  parameter Real lambda_F_z0=1 "nominal load";
  parameter Real lambda_muex=1 "peak friction coefficient";
  parameter Real lambda_muey=1 "peak friction coefficient";
  parameter Real lambda_Kx=1 "slip stiffness";
  parameter Real lambda_Ky=1 "slip stiffness";
  parameter Real lambda_Cx=1 "shape factor";
  parameter Real lambda_Cy=1 "shape factor";
  parameter Real lambda_Ex=1 "curvature factor";
  parameter Real lambda_Ey=1 "curvature factor";
  parameter Real lambda_Hx=1 "horisontal shift";
  parameter Real lambda_Hy=1 "horisontal shift";
  parameter Real lambda_Vx=1 "vertical shift";
  parameter Real lambda_Vy=1 "vertical shift";
  parameter Real lambda_gammay=1 "camber force stiffness";
  parameter Real lambda_gammaz=1 "camber torque stiffness";
  parameter Real lambda_t=1 "pneumatic trail";
  parameter Real lambda_r=1;
  parameter Real lambda_Mr=1 "residual torque";
  
  
end MFpureSlip;

VehicleDynamics.Wheels.MFTyre.MFcombinedSlip VehicleDynamics.Wheels.MFTyre.MFcombinedSlip

Parameters

NameDefaultDescription
r_Bx112.2428stiffness factor B [m]
r_Bx2-9.97521stiffness factor B [m]
r_Cx11.06866shape factor C [m]
r_Hx1-0.00618958horisontal shift H [m]
r_By15.80206stiffness factor B [m]
r_By25.87349stiffness factor B [m]
r_By31.08851stiffness factor B [m]
r_Cy11.10446shape factor C [m]
r_Hy1-0.0311875horisontal shift H [m]
r_Vy10.0620825vertical shift V [m]
r_Vy2-0.0363073vertical shift V [m]
r_Vy3-0.313050vertical shift V [m]
r_Vy423.5060vertical shift V [m]
r_Vy51.9vertical shift V [m]
r_Vy6-5.20498vertical shift V [m]
s_sz1-0.0313609 
s_sz20.0143442 
s_sz3-0.655596 
s_sz40.5 
lambda_xalpha1 
lambda_ykappa1 
lambda_Vykappa1 
lambda_s1 

Modelica definition

record MFcombinedSlip 
  //longitudinal
  parameter SI.Position r_Bx1=12.2428 "stiffness factor B";
  parameter SI.Position r_Bx2=-9.97521 "stiffness factor B";
  parameter SI.Position r_Cx1=1.06866 "shape factor C";
  parameter SI.Position r_Hx1=-0.00618958 "horisontal shift H";
  //lateral
  parameter SI.Position r_By1=5.80206 "stiffness factor B";
  parameter SI.Position r_By2=5.87349 "stiffness factor B";
  parameter SI.Position r_By3=1.08851 "stiffness factor B";
  parameter SI.Position r_Cy1=1.10446 "shape factor C";
  parameter SI.Position r_Hy1=-0.0311875 "horisontal shift H";
  parameter SI.Position r_Vy1=0.0620825 "vertical shift V";
  parameter SI.Position r_Vy2=-0.0363073 "vertical shift V";
  parameter SI.Position r_Vy3=-0.313050 "vertical shift V";
  parameter SI.Position r_Vy4=23.5060 "vertical shift V";
  parameter SI.Position r_Vy5=1.9 "vertical shift V";
  parameter SI.Position r_Vy6=-5.20498 "vertical shift V";
  
  //aligning torque
  parameter Real s_sz1=-0.0313609;
  parameter Real s_sz2=0.0143442;
  parameter Real s_sz3=-0.655596;
  parameter Real s_sz4=0.5;
  
  // User scaling Factors
  parameter Real lambda_xalpha=1;
  parameter Real lambda_ykappa=1;
  parameter Real lambda_Vykappa=1;
  parameter Real lambda_s=1;
  
end MFcombinedSlip;

VehicleDynamics.Wheels.MFTyre.MFcosine VehicleDynamics.Wheels.MFTyre.MFcosine

Modelica definition

block MFcosine 
  
  input Real x;
  input Real B;
  input Real C;
  input Real D;
  input Real E;
  
  output Real y;
equation 
  
  y = D*Modelica.Math.cos(C*Modelica.Math.atan(B*x - E*(B*x - 
    Modelica.Math.atan(B*x))));
end MFcosine;

VehicleDynamics.Wheels.MFTyre.MFsine VehicleDynamics.Wheels.MFTyre.MFsine

Modelica definition

block MFsine 
  input Real x;
  input Real B;
  input Real C;
  input Real D;
  input Real E;
  
  output Real y;
  
protected 
  Real test1;
  Real test2;
  Real bx;
equation 
  test1 = C*Modelica.Math.atan(B*x - E*(B*x - Modelica.Math.atan(B*x)));
  test2 = B*x - E*(B*x - Modelica.Math.atan(B*x));
  bx = B*x;
  
  y = D*Modelica.Math.sin(C*Modelica.Math.atan(B*x - E*(B*x - 
    Modelica.Math.atan(B*x))));
end MFsine;

VehicleDynamics.Wheels.MFTyre.MFtransient VehicleDynamics.Wheels.MFTyre.MFtransient

Parameters

NameDefaultDescription
p_Tx11.9624 
p_Tx2-0.0053684 
p_Tx3-0.31037 
lambda_sigmakappa1 
p_Ty12.3935 
p_Ty22.6895 
lambda_sigmaalpha1 

Modelica definition

record MFtransient 
  //longitudinal
  parameter Real p_Tx1=1.9624;
  parameter Real p_Tx2=-0.0053684;
  parameter Real p_Tx3=-0.31037;
  parameter Real lambda_sigmakappa=1;
  //lateral
  parameter Real p_Ty1=2.3935;
  parameter Real p_Ty2=2.6895;
  parameter Real lambda_sigmaalpha=1;
  
end MFtransient;

VehicleDynamics.Wheels.MFTyre.TyreForceTest

VehicleDynamics.Wheels.MFTyre.TyreForceTest

Modelica definition

model TyreForceTest 
  
  Wheels.MFTyre.TyreForces tyreForces;
equation 
  
  tyreForces.v_x = time;
  tyreForces.v_y = 0;
  tyreForces.w = time*4 + time*time*0.1;
  tyreForces.contact = true;
  tyreForces.gamma1 = 0;
  tyreForces.Fz = 3000;
  
end TyreForceTest;

HTML-documentation generated by Dymola Tue Jul 15 13:23:47 2003 .