Gelöste Aufgaben/JUMP/Car-Body: Unterschied zwischen den Versionen

Aus numpedia
Zur Navigation springen Zur Suche springen
Keine Bearbeitungszusammenfassung
 
(13 dazwischenliegende Versionen desselben Benutzers werden nicht angezeigt)
Zeile 31: Zeile 31:


<!------------------------------------------------------------------------->
<!------------------------------------------------------------------------->
==tmp==
{{MyNoncodeBlock
{{MyNoncodeBlock
|title=Body
|title=Body
Zeile 82: Zeile 80:
<!------------------------------------------------------------------------->
<!------------------------------------------------------------------------->


==tmp==
{{MyCodeBlock
{{MyCodeBlock
|title=Track
|title=Track
Zeile 215: Zeile 212:
}}
}}


==tmp==
{{MyNoncodeBlock
{{MyNoncodeBlock
|title=Contact-Point and -Normal
|title=Contact-Point and -Normal
Zeile 278: Zeile 274:
::<math>\tan \gamma_A(t) = \frac{\displaystyle N_{A,y}}{\displaystyle N_{A,x}}</math>.
::<math>\tan \gamma_A(t) = \frac{\displaystyle N_{A,y}}{\displaystyle N_{A,x}}</math>.


===== Track is a Parabola =====
==== Track is a Parabola ====
If the track is defined by a second-order polynomial ''p<sub>i</sub>'', we proceed accordingly. However, the track inclination is linearly dependent on “''x”'' and we find that the normal is proportional to:
If the track is defined by a second-order polynomial ''p<sub>i</sub>'', we proceed accordingly. However, the track inclination is linearly dependent on “''x”'' and we find that the normal is proportional to:


Zeile 298: Zeile 294:


<!------------------------------------------------------------------------->
<!------------------------------------------------------------------------->
==tmp==
 
{{MyNoncodeBlock
{{MyNoncodeBlock
|title=Contact Forces
|title=Contact Forces
Zeile 329: Zeile 325:
::<math>\begin{array}{ll}
::<math>\begin{array}{ll}
F &= F(N_a,v_{rel})\\
F &= F(N_a,v_{rel})\\
   & = \mu(v_{rel})\cdot N_a
   & = \mu(v_{rel})\cdot N_a - F_L
\end{array}</math>
\end{array}</math>


and introduce a point-symmetric characteristic for this relationship ''μ''(''v<sub>rel</sub>''):[[Datei:JUMP-carbody-slide22.png|mini|Friction characteristic|alternativtext=|ohne]]It mimics the key properties of dry friction with a stick-coefficient ''μ<sub>0</sub>'' for very low relative velocities and ''μ'' else. To simplify implementation, we’ll be using the same mechanism as for the tracks to compose this characteristic from lines and transition parabolas.
with the standard-formulation with ''μ''(''v<sub>rel</sub>'') for dry friction and a loss-related force ''F<sub>L</sub>''.
For the first part, we introduce a point-symmetric characteristic for this relationship ''μ''(''v<sub>rel</sub>''):[[Datei:JUMP-carbody-slide22.png|mini|Friction characteristic|alternativtext=|ohne]]It mimics the key properties of dry friction with a stick-coefficient ''μ<sub>0</sub>'' for very low relative velocities and ''μ'' else. To simplify implementation, we’ll be using the same mechanism as for the tracks to compose this characteristic from lines and transition parabolas.
 
The latter part for ''F<sub>L</sub>'' represents a force that is required to push the elastic wheel through elasto-plastic ground. We'll keep it simple and phrase it to be
 
::<math>F_L = \mu \cdot N_a \cdot \frac{\displaystyle 2}{\displaystyle \pi} \text{atan}\left( \frac{\displaystyle v_T}{\displaystyle v_{T 0}}\right) </math>
 
with the new loss-velocity ''v<sub>T0<sub>''. The atan-function looks somewhat displaced here - it ensures that the rolling loss-force does not exceed the traction force.
|code=
|code=
<syntaxhighlight lang="lisp" line start=1>
<syntaxhighlight lang="lisp" line start=1>
Zeile 397: Zeile 400:
::<math>\delta \underline{r}_b = \begin{pmatrix}{a_2} \sin{\left( \operatorname{\varphi }(t)\right) } \mathit{\delta \varphi }-\left( {u_4}(t)-{a_3}\right)  \cos{\left( \operatorname{\varphi }(t)\right) } \mathit{\delta \varphi }-{{\mathit{\delta u}}_4} \sin{\left( \operatorname{\varphi }(t)\right) }+{{\mathit{\delta u}}_1}\\
::<math>\delta \underline{r}_b = \begin{pmatrix}{a_2} \sin{\left( \operatorname{\varphi }(t)\right) } \mathit{\delta \varphi }-\left( {u_4}(t)-{a_3}\right)  \cos{\left( \operatorname{\varphi }(t)\right) } \mathit{\delta \varphi }-{{\mathit{\delta u}}_4} \sin{\left( \operatorname{\varphi }(t)\right) }+{{\mathit{\delta u}}_1}\\
-\left( {u_4}(t)-{a_3}\right)  \sin{\left( \operatorname{\varphi }(t)\right) } \mathit{\delta \varphi }-{a_2} \cos{\left( \operatorname{\varphi }(t)\right) } \mathit{\delta \varphi }+{{\mathit{\delta u}}_4} \cos{\left( \operatorname{\varphi }(t)\right) }+{{\mathit{\delta u}}_2}\end{pmatrix}</math>.
-\left( {u_4}(t)-{a_3}\right)  \sin{\left( \operatorname{\varphi }(t)\right) } \mathit{\delta \varphi }-{a_2} \cos{\left( \operatorname{\varphi }(t)\right) } \mathit{\delta \varphi }+{{\mathit{\delta u}}_4} \cos{\left( \operatorname{\varphi }(t)\right) }+{{\mathit{\delta u}}_2}\end{pmatrix}</math>.
==tmp==


{{MyCodeBlock
{{MyCodeBlock
Zeile 412: Zeile 413:


<!------------------------------------------------------------------------->
<!------------------------------------------------------------------------->
==tmp==
{{MyCodeBlock
{{MyCodeBlock
|title=Virtual Work of External Forces - including D'Alembert Forces
|title=Virtual Work of External Forces - including D'Alembert Forces
|text=The components of virtual work of external forces are
|text=The components of virtual work of external forces are


<math>\delta W^a = \delta W^a_g + \delta W^a_A + \delta W^a_d + \delta W^a_F</math>
::<math>\delta W^a = \delta W^a_g + \delta W^a_A + \delta W^a_d + \delta W^a_F</math>


where
where
Zeile 428: Zeile 428:
With the principle of virtual work, we phrase
With the principle of virtual work, we phrase


<math>\delta W_g^a =  
::<math>\delta W_g^a =  
- m_C\; g  \; \vec{e}_y \cdot \delta\vec{r}_C
- m_C\; g  \; \vec{e}_y \cdot \delta\vec{r}_C
- m_A\; g  \; \vec{e}_y \cdot \delta\vec{r}_A
- m_A\; g  \; \vec{e}_y \cdot \delta\vec{r}_A
- m_B\; g  \; \vec{e}_y \cdot \delta\vec{r}_B</math>,
- m_B\; g  \; \vec{e}_y \cdot \delta\vec{r}_B</math>,


<math>\delta W_A^a =
::<math>\delta W_A^a =
- m_C\;\ddot{\vec{r}}_C \cdot \delta\vec{r}_C
- m_C\;\ddot{\vec{r}}_C \cdot \delta\vec{r}_C
- m_A\;\ddot{\vec{r}}_A \cdot \delta\vec{r}_A
- m_A\;\ddot{\vec{r}}_A \cdot \delta\vec{r}_A
Zeile 440: Zeile 440:
- J_A\;\ddot{\psi} \cdot \delta\psi</math>,
- J_A\;\ddot{\psi} \cdot \delta\psi</math>,


<math>\delta W_d^a = b_3 \, \dot{u}_3 \cdot \delta u_3
::<math>\delta W_d^a = b_3 \, \dot{u}_3 \cdot \delta u_3
                       + b_4 \, \dot{u}_4 \cdot \delta u_4
                       + b_4 \, \dot{u}_4 \cdot \delta u_4
                       + B \, \left(\omega(t)+\Omega(t) \right) \cdot
                       + B \, \left(\omega(t)+\Omega(t) \right) \cdot
Zeile 447: Zeile 447:
and
and


<math>\delta W_F^a =  
::<math>\delta W_F^a =  
\underline{\underline{D}}(\gamma_A)\cdot \left(\begin{array}{c}T\\N_A\end{array}\right) \cdot  \delta\underline{r}_a
\underline{\underline{D}}(\gamma_A)\cdot \left(\begin{array}{c}T\\N_A\end{array}\right) \cdot  \delta\underline{r}_a
+ \underline{\underline{D}}(\gamma_B)\cdot \left(\begin{array}{c}0\\N_B\end{array}\right) \cdot \delta\underline{r}_b
+ \underline{\underline{D}}(\gamma_B)\cdot \left(\begin{array}{c}0\\N_B\end{array}\right) \cdot \delta\underline{r}_b
Zeile 454: Zeile 454:
We group all components of by their virtual displacements , the coefficient of each virtual displacement being one equilibrium condition. The resultant equations have this form:
We group all components of by their virtual displacements , the coefficient of each virtual displacement being one equilibrium condition. The resultant equations have this form:


<math>\delta W = \delta \underline{q}_C \cdot \left(-\underline{\underline{M}}\cdot\ddot{\underline{q}} + \underline{f}(\dot{\underline{q}},\underline{q})\right)</math>.
::<math>\delta W = \delta \underline{q}_C \cdot \left(-\underline{\underline{M}}\cdot\ddot{\underline{q}} + \underline{f}(\dot{\underline{q}},\underline{q})\right)</math>.
|code=
|code=
<syntaxhighlight lang="lisp" line start=1>
<syntaxhighlight lang="lisp" line start=1>
1+1=2
/*******************************************************/
/* MAXIMA script                                      */
/* version: wxMaxima 16.04.2                          */
/* author: Andreas Baumgart                            */
/* last updated: 2021-02-08                            */
/* ref: Modelling and Simulation (TUAS)                */
/* description: Rounding between straight line-segments*/
/*******************************************************/
 
/*******************************************************/
/* declarations                                        */
/*******************************************************/
declare("λ", alphabetic);
declare("Δ", alphabetic);
declare("δ", alphabetic,"ε", alphabetic);
declare("Π", alphabetic);
declare("φ", alphabetic);
declare("ψ", alphabetic);
declare("κ", alphabetic);
declare("α", alphabetic);
declare("γ", alphabetic);
declare("ω", alphabetic);
 
/*******************************************************/
/* body centers                                        */
/*******************************************************/
/* car body */
r[C] : [u[1](t),u[2](t)];
D[1](α) := matrix([cos(α),-sin(α)],[sin(α),cos(α)]);
 
/* wheel centers - reference configuration */
r[A] : r[C] + D[1](φ(t)).matrix([+a[1]],[-a[3]+u[3](t)]);
r[B] : r[C] + D[1](φ(t)).matrix([-a[2]],[-a[3]+u[4](t)]);
 
/* wheel contacts */
 
local : [γ[A](t) = φ(t) + (κ(t)-ψ(t))];
r[a] : r[A] + D[1](γ[A](t)).matrix([0],[-R]);
r[b] : r[B] + D[1](γ[B](t)).matrix([0],[-R]);
 
varia: append(makelist(u[i](t) =  u[i](t) + ε*δu[i],i,1,4),[φ(t) = φ(t) + ε*δφ, ψ(t) = ψ(t) + ε*δψ]);
 
q  : append(makelist( u[i](t),i,1,4), [ φ(t), ψ(t)]);
δq : append(makelist(δu[i]  ,i,1,4), [δφ  ,δψ  ]);
nuller : makelist(q[i]=0, i,1,length(q));
 
δr[C] : sum(subst([ε=0],diff(subst(varia[i],r[C]),ε)),i,1,length(varia));
δr[A] : sum(subst([ε=0],diff(subst(varia[i],r[A]),ε)),i,1,length(varia));
δr[B] : sum(subst([ε=0],diff(subst(varia[i],r[B]),ε)),i,1,length(varia));
δr[a] : sum(subst([ε=0],diff(subst(varia[i],subst(local,r[a])),ε)),i,1,length(varia));
δr[b] : sum(subst([ε=0],diff(subst(varia[i],subst(local,r[b])),ε)),i,1,length(varia));
 
/* d'Alembert Forces */
δW[I] : expand(-m[1]*diff(r[C],t,2).δr[C] - m[2]*diff(r[A],t,2).δr[A] - m[2]*diff(r[B],t,2).δr[B] - J[1]*diff(φ(t),t,2)*δφ - J[2]*diff(ψ(t),t,2)*δψ);
δW[I] : expand(subst(['diff(φ(t),t,1)^2=0],δW[I]));
 
/* Springs / Dampers*/
δΠ : (k[1]*u[3](t)+b[1]*diff(u[3](t),t))*δu[3]+(k[2]*u[4](t)+b[2]*diff(u[4](t),t))*δu[4];
δΠ : expand(δΠ);
 
/* Motor (δφ has the opposite orientation of δψ) */
δW[m] : MW*δψ;
 
/* Weight */
δW[G] : -m[1]*g*δu[2] - m[2]*g*δr[A][2] - m[2]*g*δr[B][2];
 
/* Contact*/
δW[c] : δr[a].(D[1](γ[A]).[F[T],F[N1]]) + δr[b].(D[1](γ[2]).[0,F[N2]]);
δW[c] : expand(subst(solve(local,κ(t))[1],δW[c]));
 
/*--------------------------------------------------*/
δW[total] : expand(δW[I] - δΠ + δW[G] + δW[c] + δW[m]);
 
eom : expand(makelist(coeff(δW[total][1],δq[i]),i,1,length(δq)));
δW[rest] : expand(δW[total][1] -sum(eom[i]*δq[i],i,1,length(δq)));
 
M : funmake('matrix,makelist(makelist(coeff(eom[row],diff(q[col],t,2)),col,1,length(q)),row,1, length(q)));
trigRepl : [solve(cos(γ[B]-φ(t)) = trigexpand(cos(γ[B]-φ(t))),sin(γ[B]))[1],
            solve(cos(γ[A]-φ(t)) = trigexpand(cos(γ[A]-φ(t))),sin(γ[A]))[1],
            solve(sin(γ[A]-φ(t)) = trigexpand(sin(γ[A]-φ(t))),cos(γ[A]))[1]];
 
rightHandS : expand(makelist(eom[row] - sum(M[row,col]*diff(q[col],t,2),col,1,length(q)),row,1, length(q)));
/* neglect the impact of deflections u[3], u[4] on the mass moment of the total car */
/* further simplifications of intertial forces */
rightHandS[1]:ratsimp(trigsimp(subst(['diff(u[3](t),t,1)=0,'diff(u[4](t),t,1)=0],rightHandS[1])));
rightHandS[2]:ratsimp(trigsimp(subst(['diff(u[3](t),t,1)=0,'diff(u[4](t),t,1)=0],rightHandS[2])));
 
tmp          : F[N1]*subst(trigRepl[2],coeff(rightHandS[3],F[N1]))+
              F[T] *subst(trigRepl[3],coeff(rightHandS[3],F[T] ));
rightHandS[3]: tmp+ratsimp(trigexpand(rightHandS[3]-tmp));
rightHandS[4]: ratsimp(subst(trigRepl,rightHandS[4]));
 
rightHandS[5]:subst(['diff(u[3](t),t,1)=0,'diff(u[4](t),t,1)=0],rightHandS[5]);
trigRepl : [cos(γ[A]-φ(t)) = trigexpand(cos(γ[A]-φ(t))),
            cos(γ[B]-φ(t)) = trigexpand(cos(γ[B]-φ(t))),
    sin(γ[A]-φ(t)) = trigexpand(sin(γ[A]-φ(t))),
    sin(γ[B]-φ(t)) = trigexpand(sin(γ[B]-φ(t)))];
/* need to get rid of the Minus-signs .... */
assume(cos(γ[A])>0,cos(γ[B])>0,sin(γ[A])>0,sin(γ[B])>0,sin(φ(t))>0,cos(φ(t))>0);
for i:1 thru 4 do
    (trigRepl[i] : trigRepl[i] - part(rhs(trigRepl[i]),1),
    trigRepl[i] : rhs(trigRepl[i]) = lhs(trigRepl[i]),
    if is(lhs(trigRepl[i])<0) then
    trigRepl[i] : -trigRepl[i]);
abbrev : solve([a[3]-u[3](t)=Δu[3], a[3]-u[4](t)=Δu[3]],[u[3](t),u[4](t)])[1];
collector : [[F[N1],F[N2],F[T]],[a[1],a[2],a[3]]];
tmp : makelist(makelist(coeff(coeff(rightHandS[5],collector[1][i]),collector[2][j]),j,1,3),i,1,3);
tmp : subst(trigRepl,tmp);
tmp : sum(sum(tmp[i][j]*collector[1][i]*collector[2][j],j,1,3),i,1,3);
rightHandS[5]: trigsimp(ratsimp(expand(tmp+ratsimp(trigexpand(rightHandS[5]-tmp)))));
 
/* ... now simplify mass matrix */
M : -subst(nuller,M);
for row:1 thru 5 do
    (for col:row thru 5 do
    print("M(",row,",",col,") = ",M[row][col]))$
 
/* and print right-hand-side */
for i:1 thru length(q)  do
  (grind(trigsimp(ratsimp(rightHandS[i]))),
    print("---------------------------------------------------"))$
 
/* tnslate */
toDyDt : [cos(γ[A]) = cosgamma[1],cos(γ[B]) = cosgamma[2],
          sin(γ[A]) = singamma[1],sin(γ[B]) = singamma[2],
  cos(φ(t)) = cosphi, sin(φ(t)) = sinphi,  
          'diff(u[3](t),t,1) = v[3],  
          'diff(u[4](t),t,1) = v[4]]
for i:1 thru length(q)  do
  (print(trigsimp(ratsimp(subst(toDyDt,rightHandS[i])))),
    print("---------------------------------------------------"))$
/************************************************************************/
/* start vector */
starter : append(makelist('diff(u[i](t),t,1)=0,i,1,4),
        [sin(φ(t))=0,cos(φ(t))=1,'diff(φ(t),t,1)=0],
      [F[N1]=0,F[N2]=0,F[T]=0, MW=0]);
 
atStart : makelist(subst(starter,eom)[i]=0,i,1,length(q));
TT : append(makelist(diff(u[i](t),t,2),i,1,4),['diff(φ(t),t,2),'diff(ψ(t),t,2)]);
START : solve(atStart, TT)[1];
 
makelist(lhs(START[i])=subst([u[3](t)=0,u[4](t)=0],rhs(START[i])),i,1,length(q));
 
/************************************************************************/
/* translate to first-order DGL */
toDyDt: ['diff(u[1](t),t,1) = Q[ 1],
      'diff(u[2](t),t,1) = Q[ 2],
      'diff(u[3](t),t,1) = Q[ 3],
      'diff(u[4](t),t,1) = Q[ 4],
      'diff(  φ(t),t,1) = Q[ 5],
      'diff(  ψ(t),t,1) = Q[ 6],
      u[1](t)     = Q[ 7],
            u[2](t)     = Q[ 8],
            u[3](t)     = Q[ 9],
            u[4](t)     = Q[10],
            φ(t)        = Q[11],
          sin(Q[11])      = sinphi,
          cos(Q[11])      = cosphi];
 
rhside : ratsimp(subst(toDyDt,rightHandS));
 
for i:1 thru 6  do
  (print("rhs(",i,") = ",ratsimp(rhside[i])),
    print("---------------------------------------------------"))$
 
 
taylor : [cos(φ(t)) = 1-φ(t)^2/2!,sin(φ(t)) = φ(t)-φ(t)^3/3!];plot2d([sin(phi), phi-phi^3/3!],[phi, -%pi/2, %pi/2])$
 
 
 
/* velocity in contact point */
/* of axles ..... */
/* im Reference-System */
v[A] : trigsimp(diff(r[A],t));
v[B] : trigsimp(diff(r[B],t));
 
/* Transformation ins surface-system*/
V[a] : D[1](-γ[A]).[V[3],V[4]]+[-R*ω,0];
V[v] : D[1](-γ[B]).[V[5],V[6]];
 
/***************************** using formal approach ******************************/
/* in reference-coordinates */
/* axle "1" */
reverse : solve(local,κ(t))[1];
v[a] : subst([reverse, diff(reverse,t)], diff(subst(local,r[a]),t));
v[a] : subst([diff(ψ(t),t)=ω(t)], subst(subst(['diff(κ(t),t,1)=0],diff(local,t,1)), ev(v[a],nouns)));
/* in surface - coordinates */
V[a] : trigsimp(expand(D[1](-γ[A]).v[a]));
 
/* axle "2" */
v[b] : diff(subst(local,r[b]),t);
/* in surface - coordinates */
V[b] : trigsimp(expand(D[1](-γ[B]).v[b]));
</syntaxhighlight>
</syntaxhighlight>
}}
}}
Zeile 494: Zeile 686:
!unit
!unit
|-
|-
|''m<sub>C</sub>''
|''u<sub>1</sub>''
|
|center of mass displacement in x-direction
|
|m
|-
|''u<sub>2</sub>''
|center of mass displacement in y-direction
|m
|-
|''u<sub>3</sub>''
|spring compression at front axis
|m
|-
|''u<sub>4</sub>''
|spring compression at rear axis
|m
|-
|-
|
|''ϕ''
|
|rotation of car-body
|
|rad
|-
|-
|
|''ψ''
|
|rotation of wheel (absolute - not relative to car-body)
|
|rad
|}
|}


Zeile 511: Zeile 715:
!name
!name
!symbol
!symbol
!value
!unit
!unit
|-
|-
|mass of car-body
|axis distance
|m<sub>C</sub>
|''a<sub>0</sub>''
|40
|cm
|-
|distance front axis center of mass
|''a<sub>1</sub>''
|10
|cm
|- a[3] 0.1 m
|vertical distance from wheel-hub to center of mass for relaxed springs
|''a<sub>3</sub>''
|10
|cm
|-
|wheel radius
|''R''
|58.42
|mm
|-
|car-body mass
|''m<sub>C</sub>''
|4
|kg
|kg
|-
|-
|mass of wheel-pair "''A''"
|wheel-set mass
|m<sub>A</sub>
|''m<sub>W</sub>''
|0.3
|kg
|kg
|-
|-
|mass of wheel-pair "''A''"
|inertia-radius for body with <math>J_C = m_C \cdot r_C^2</math>
|m<sub>B</sub>
|''r<sub>C</sub>''
|kg
|15
|cm
|-
|inertia-radius wheel-set
|''r<sub>W</sub>''
|4
|cm
|-
|track-stiffness
|''k<sub>T</sub>''
|1.00E+04
|N/m
|-
|spring stiffness front
|''k<sub>1</sub>''
|500
|N/m
|-
|spring stiffness rear;<br/> if "0" is given, compute it so that the static ''ϕ=0''
|''k<sub>2</sub>''
|0
|N/m
|-
|spring damping front
|''b<sub>1</sub>''
|100
|N/(m/s)
|-
|spring damping rear
|''b<sub>2</sub>''
|100
|N/(m/s)
|-
|smoothening radius for spring characteristic
|''ε''
|1
|mm
|-
|friction coefficient
|''μ''
|0.4
|1
|-
|rounding radius for friction coefficient
|''μ<sub>ε</sub>''
|0.01
|1
|-
|stick coefficient
|''μ<sub>0</sub>''
|0.6
|1
|-
|reference velocity for damping at springs
|''v<sub>ref</sub>''
|5
|m/s
|-
|-
| colspan="1" |mass-moment of car-body
|loss velocity for rolling contact
| colspan="1" |''J<sub>C</sub>''
|''v<sub>T0</sub>''
| colspan="1" |kg m<sup>2</sup>
|5
|m/s
|}
|}
[[Gelöste Aufgaben/JUMP/Driver Controls|next workpackage: driver-controls →]]
[[Gelöste Aufgaben/JUMP/Driver Controls|next workpackage: driver-controls →]]



Aktuelle Version vom 24. März 2021, 13:08 Uhr

← Back to Start

Scope

Car-Body

In common simulation applications - especially for full-size commercial cars - the pitch-angle of the car is assumed to be small to allow for a linearization of geometry and most parts of the equations of motion. We drop this limitation so we can do more fancy stuff with our model - like climbing steep roads or jumping across ditches.

Block Diagram.

We employ a spatial x-y coordinate system, x in horizontal, y in vertical, upwards direction. And we’ll briefly employ the z-axis as rotation direction - which is towards you following the “right-hand-rule“ for coordinate systems.

Structure

The driver controls the car's motion via the position of the "gas"-pedal, which is being translated into a torque MW at the wheel.

This toque will change velocities and thus the position of the car. These state-variables will then create - via info - a feedback to the driver.

We’ll need to invest significant efforts in describing the kinematics of the car-motion and to derive its equations of body-motion since we do not want to limit our study on small pitch-angles of the car. Key accessory will be vectors, which map locations like the center of mass:

.

This vector has - in 2D - two coordinates , measured in the inertial x-y frame:

with .

representing the unit vectors spanning the x-y space. If we refer to a specific frame, we may drop the vector-notation and refer to the column-matrix of coordinates only, so

.

We’ll also employ coordinate transformations using Euler-rotations.

The car with front-wheel drive consists of the car-body with center of mass “C“, the front wheels “A“ and the rear wheel “B“. Masses of car-body and wheel-sets are M and m respectively.The geometry of the car is described by

  • a0: the wheel base;
  • a1: longitudinal distance between center of mass and front-wheel-hub;
  • a2 = a0 - a1 and
  • a3: vertical distance between center of mass and front-wheel-hub (relaxed springs).

Body

We use five coordinates to describe the motion of the car:

  • for the location of the center of mass of the car-body and its pitch-angle
    ,
  • for the "vertical" motion of the wheel hubs relative to the car-body - which is synonym to the compression of the springs

    and
  • as the rotation angle of the front-wheel - we'll not account for the rotation of the rear-wheel.

So the center of mass of the car-body is

,

the coordinate system of the car is

where

.

So the location of the front-wheel “A“ is

or

.

Likewise, the location of the rear-wheel “B“ is

and in the following, we’ll be using the abbreviations

and

.


Track

Tack specification

We describe the road by road-sections, which we call tracks. We start by defining each track as a line-segment, i.e. a first-order polynomial. The road is thus defined by pairs of track-endpoints, i.e. (xi, yi).

The track-polynomials are

.

During the numerical integration of the initial-value-problem - when the car runs along the track - the solver needs to cope with the transition between two straight lines - which is numerically more efficient if we convert the road in a continuously differentiable function.

Rounding the edges.

For this purpose, we define transition polynomials pi of second degree - parabolas - as

which connect two neighboring tracks.

The boundary conditions for the parabolas (red) and the neighboring lines (blue) yield

And though we have four boundary conditions, they allow for a solution with three unknown polynomial coefficients Pi if Δxi is identical left and right from xi - which we have already implied.

and

But instead of employing the above, we solve the linear systems of equations for the coefficients numerically.

Now each polynomial creates new endpoints xi - Δxi and xi + Δxi which substitute for the initial xi-point. The tracks are represented by a succession of lines and parabolas.

Next we need to find the contact point between wheel and road!


/*******************************************************/
/* MAXIMA script                                       */
/* version: wxMaxima 16.04.2                           */
/* author: Andreas Baumgart                            */
/* last updated: 2021-02-08                            */
/* ref: Modelling and Simulation (TUAS)                */
/* description: Rounding between straight line-segments*/
/*******************************************************/

/*******************************************************/
/* declarations                                        */
/*******************************************************/
declare("Δ",alphabetic);

params: [x[0] = 0, x[1] = 10, x[2]=15,
         y[0] = 0, y[1] =  1, y[2]=-1,
	 eps = 0.2];

/*******************************************************/
/* polynomials                                         */
/*******************************************************/
/* polynomial coefficiets of two consecutive straigt lines */
P : [[a[1,1],a[1,0]],[a[2,1],a[2,0]]];
/* polynomials of cubic and two consecutive linear polynomials */
p : [a[1,1]*x+a[1,0],
     b[3]*x^3+b[2]*x^2+b[1]*x+b[0],
     a[2,1]*x+a[2,0]];

/* compute polynomial coefficients from (x[i]/y[i])-points*/
linear : solve([subst([x=x[0]],p[1]) = y[0],
                subst([x=x[1]],p[1]) = y[1],
		subst([x=x[1]],p[3]) = y[1],
		subst([x=x[2]],p[3]) = y[2]], [a[1,0],a[1,1],a[2,0],a[2,1]])[1];
/* equations to continuously fit cubic function to lines */
equs : [subst([x=x[1]-Δx], p[1]) = subst([x=x[1]-Δx], p[2]),
        subst([x=x[1]+Δx], p[3]) = subst([x=x[1]+Δx], p[2]),
	subst([x=x[1]-Δx], diff(p[1],x)) = subst([x=x[1]-Δx], diff(p[2],x)),
	subst([x=x[1]+Δx], diff(p[3],x)) = subst([x=x[1]+Δx], diff(p[2],x))];
/* unknowns */
Q : [b[3],b[2],b[1],b[0]];

/* solve for unknowns */
sol : ratsimp(subst(linear,solve(equs,Q)[1]));

/* solve linear system of equations for unknown coefficients */
ACM : augcoefmatrix(equs,Q);
print(submatrix(ACM,5)," * ",transpose(Q)," = ",col(ACM,5))$


/* or - more simple when doing it numerically  .... */

/* coefficients of straigt line polynomials */
s : makelist(a[i,1] = (y[i-1]-y[i])/(x[i-1]-x[i]),i,1,2);

P : [[a[1,1],a[1,0]],[a[2,1],a[2,0]]];
p : [a[1,1]*x+a[1,0],
     b[3]*x^3+b[2]*x^2+b[1]*x+b[0],
     a[2,1]*x+a[2,0]];

linear : solve([subst([x=x[1]],p[1]) = y[1],
		subst([x=x[1]],p[3]) = y[1]], [a[1,0],a[2,0]])[1];

equs : [subst([x=x[1]-Δx], p[1]) = subst([x=x[1]-Δx], p[2]),
        subst([x=x[1]+Δx], p[3]) = subst([x=x[1]+Δx], p[2]),
	subst([x=x[1]-Δx], diff(p[1],x)) = subst([x=x[1]-Δx], diff(p[2],x)),
	subst([x=x[1]+Δx], diff(p[3],x)) = subst([x=x[1]+Δx], diff(p[2],x))];
Q : [b[3],b[2],b[1],b[0]];

sol : ratsimp(subst(linear,solve(equs,Q)))[1];

/* check with parameters */
subst(params,subst(s,subst(linear,solve(equs,Q))));




Contact-Point and -Normal

Contact conditions.

Finding the contact between wheel and road is our next challenge. We need to differentiate between the straight lines and the parabolas - but in both cases, we are looking for the equation of the normal “N“ to the road-surface, which cuts through the wheel-hub.

From the car-coordinates, we know the location of the wheel - e.g. “A” - expressed by its hub-vector

.

And we can also define

.

where  is the vector to the contact point “a“ of wheel “A“ and is the vector from “a“ to the wheel hub “A“. Since "a" is a point on a track - if wheel and road have contact - and the direction of NA is known to be perpendicular to this track in “a”, we have two equations for the two unknowns “point on track“ and “length of normal “.

Contact angles

However, it remains tricky to find the material coordinate of the wheel that is at “a“. The picture below explains how first rotate the car by φ - positive about the z-axis, then rotate the wheel in negative direction by ψ and by κ in positive direction back to vertical. From there it is the known angle γA to “a“.

This succession of rotations is expressed by

and we find contact point “a“ from

and “b“ from

.

For wheel A und B, the angles ψ and κ are not identical - but we have dropped the indices here for brevity.

Track is a Line

If the track is line “i“, we have

with

being start- end end-points of the line with coordinates [xi, hi] and ξ naming the coordinate of point “C“. For the track-normal, we have

with the unit-normal , the wheel-radius R and the unknown η. For the unit-normal

holds.

And for the contact angles γA/B we employ

.

Track is a Parabola

If the track is defined by a second-order polynomial pi, we proceed accordingly. However, the track inclination is linearly dependent on “x” and we find that the normal is proportional to:

From

we get two equations for the unknowns “x“ and “η“ as

.

And we get a third-degree polynomial in “x“ from the second equation. The three solutions for point “C” usually comprise complex (they have a real and imaginary part) solutions depending on the curvature (convex or concave) of the parabola. That’s not a problem but increases computational cost significantly - because we will need to solve this equation for each value of U3, U4 again and again.


Contact Forces

Wheel kinematics

At contact “a” between road and wheel, the motor-torque must be transformed into a propulsion force of the car.

In the freebody-diagram for wheel “A“ below, we account for the contact forces

  • normal force Na and
  • traction force F.

The interaction between road and wheel is a complex relationship between these two forces and the relative velocity vrel of the wheel in point C relative to the road.

Contact forces F, N

For the normal force NA we assume a characteristic which depends on the dimensionless compression of the wheel e = 1-η, where - obviously -

To have a continuously differentiable function NA as in this contact-characteristic, we choose a parabola for 0<e<ε with continuous transitions to

  • e=0 for e<0 and
  • e=kC η for e>ε:
    Characteristic for contact force.

And - for the sake of simplicity - let

.

Now, for the traction force, we assume

with the standard-formulation with μ(vrel) for dry friction and a loss-related force FL.

For the first part, we introduce a point-symmetric characteristic for this relationship μ(vrel):

Friction characteristic

It mimics the key properties of dry friction with a stick-coefficient μ0 for very low relative velocities and μ else. To simplify implementation, we’ll be using the same mechanism as for the tracks to compose this characteristic from lines and transition parabolas.

The latter part for FL represents a force that is required to push the elastic wheel through elasto-plastic ground. We'll keep it simple and phrase it to be

with the new loss-velocity vT0. The atan-function looks somewhat displaced here - it ensures that the rolling loss-force does not exceed the traction force.


Model

For this geometrically nonlinear system, it is a challenge to derive the equations of motion. We’ll be employing the Principle of Virtual Work with the equilibrium condition stating that the sum of all virtual work at the point of equilibrium vanishes:

with the virtual strain energy δΠ and the virtual work of external forces δWa. These equilibrium conditions will deliver the nonlinear equations of motion for the minimal-coordinates of the car

.

The inertia-forces for the equilibrium conditions result form accelerations, i.e. second order time-derivatives of these coordinates. Thus, we have their velocities as further state variables. Well, except for the wheel-rotation-angle ψ(t), which we are not interested in. With

we collect all state variables of the system as

.

When deriving the equations of motion with the principle of virtual displacements we also need the variations of rC, rA, rB with respect to QC,. They come from

,

thus

,
,
,

and - not accounting for ψ and κ - as

.

Virtual Strain Energy

The only elastic elements in our car are the two springs, thus

.

/* in next section ... */




Virtual Work of External Forces - including D'Alembert Forces

The components of virtual work of external forces are

where

  • δWag: virtual work of gravitational forces,
  • δWaA: virtual work of D'Alembert inertia forces,
  • δWad: virtual work of dissipative forces (dampers parallel to the suspension springs / rotational damping) and
  • 'δWaF': virtual work of implied forces and moments like NA, NB, F and MW.

With the principle of virtual work, we phrase

,
,

and

.

We group all components of by their virtual displacements , the coefficient of each virtual displacement being one equilibrium condition. The resultant equations have this form:

.

/*******************************************************/
/* MAXIMA script                                       */
/* version: wxMaxima 16.04.2                           */
/* author: Andreas Baumgart                            */
/* last updated: 2021-02-08                            */
/* ref: Modelling and Simulation (TUAS)                */
/* description: Rounding between straight line-segments*/
/*******************************************************/

/*******************************************************/
/* declarations                                        */
/*******************************************************/
declare("λ", alphabetic);
declare("Δ", alphabetic);
declare("δ", alphabetic,"ε", alphabetic);
declare("Π", alphabetic);
declare("φ", alphabetic);
declare("ψ", alphabetic);
declare("κ", alphabetic);
declare("α", alphabetic);
declare("γ", alphabetic);
declare("ω", alphabetic);

/*******************************************************/
/* body centers                                        */
/*******************************************************/
/* car body */
r[C] : [u[1](t),u[2](t)];
D[1](α) := matrix([cos(α),-sin(α)],[sin(α),cos(α)]);

/* wheel centers - reference configuration */
r[A] : r[C] + D[1](φ(t)).matrix([+a[1]],[-a[3]+u[3](t)]);
r[B] : r[C] + D[1](φ(t)).matrix([-a[2]],[-a[3]+u[4](t)]);

/* wheel contacts */

local : [γ[A](t) = φ(t) + (κ(t)-ψ(t))];
r[a] : r[A] + D[1](γ[A](t)).matrix([0],[-R]);
r[b] : r[B] + D[1](γ[B](t)).matrix([0],[-R]);

varia: append(makelist(u[i](t) =  u[i](t) + ε*δu[i],i,1,4),[φ(t) = φ(t) + ε*δφ, ψ(t) = ψ(t) + ε*δψ]); 

q  : append(makelist( u[i](t),i,1,4), [ φ(t), ψ(t)]);
δq : append(makelist(δu[i]   ,i,1,4), [δφ   ,δψ   ]);
nuller : makelist(q[i]=0, i,1,length(q));

δr[C] : sum(subst([ε=0],diff(subst(varia[i],r[C]),ε)),i,1,length(varia));
δr[A] : sum(subst([ε=0],diff(subst(varia[i],r[A]),ε)),i,1,length(varia));
δr[B] : sum(subst([ε=0],diff(subst(varia[i],r[B]),ε)),i,1,length(varia));
δr[a] : sum(subst([ε=0],diff(subst(varia[i],subst(local,r[a])),ε)),i,1,length(varia));
δr[b] : sum(subst([ε=0],diff(subst(varia[i],subst(local,r[b])),ε)),i,1,length(varia));

/* d'Alembert Forces */
δW[I] : expand(-m[1]*diff(r[C],t,2).δr[C] - m[2]*diff(r[A],t,2).δr[A] - m[2]*diff(r[B],t,2).δr[B] - J[1]*diff(φ(t),t,2)*δφ - J[2]*diff(ψ(t),t,2)*δψ);
δW[I] : expand(subst(['diff(φ(t),t,1)^2=0],δW[I]));

/* Springs / Dampers*/
δΠ : (k[1]*u[3](t)+b[1]*diff(u[3](t),t))*δu[3]+(k[2]*u[4](t)+b[2]*diff(u[4](t),t))*δu[4];
δΠ : expand(δΠ);

/* Motor (δφ has the opposite orientation of δψ) */
δW[m] : MW*δψ;

/* Weight */
δW[G] : -m[1]*g*δu[2] - m[2]*g*δr[A][2] - m[2]*g*δr[B][2];

/* Contact*/
δW[c] : δr[a].(D[1](γ[A]).[F[T],F[N1]]) + δr[b].(D[1](γ[2]).[0,F[N2]]);
δW[c] : expand(subst(solve(local,κ(t))[1],δW[c]));

/*--------------------------------------------------*/
δW[total] : expand(δW[I] - δΠ + δW[G] + δW[c] + δW[m]);

eom : expand(makelist(coeff(δW[total][1],δq[i]),i,1,length(δq)));
δW[rest] : expand(δW[total][1] -sum(eom[i]*δq[i],i,1,length(δq)));

M : funmake('matrix,makelist(makelist(coeff(eom[row],diff(q[col],t,2)),col,1,length(q)),row,1, length(q)));
trigRepl : [solve(cos(γ[B]-φ(t)) = trigexpand(cos(γ[B]-φ(t))),sin(γ[B]))[1],
            solve(cos(γ[A]-φ(t)) = trigexpand(cos(γ[A]-φ(t))),sin(γ[A]))[1],
            solve(sin(γ[A]-φ(t)) = trigexpand(sin(γ[A]-φ(t))),cos(γ[A]))[1]];

rightHandS : expand(makelist(eom[row] - sum(M[row,col]*diff(q[col],t,2),col,1,length(q)),row,1, length(q)));
/* neglect the impact of deflections u[3], u[4] on the mass moment of the total car */
/* further simplifications of intertial forces */
rightHandS[1]:ratsimp(trigsimp(subst(['diff(u[3](t),t,1)=0,'diff(u[4](t),t,1)=0],rightHandS[1])));
rightHandS[2]:ratsimp(trigsimp(subst(['diff(u[3](t),t,1)=0,'diff(u[4](t),t,1)=0],rightHandS[2])));

tmp          : F[N1]*subst(trigRepl[2],coeff(rightHandS[3],F[N1]))+
               F[T] *subst(trigRepl[3],coeff(rightHandS[3],F[T] ));
rightHandS[3]: tmp+ratsimp(trigexpand(rightHandS[3]-tmp));
rightHandS[4]: ratsimp(subst(trigRepl,rightHandS[4]));

rightHandS[5]:subst(['diff(u[3](t),t,1)=0,'diff(u[4](t),t,1)=0],rightHandS[5]);
trigRepl : [cos(γ[A]-φ(t)) = trigexpand(cos(γ[A]-φ(t))),
            cos(γ[B]-φ(t)) = trigexpand(cos(γ[B]-φ(t))),
	    sin(γ[A]-φ(t)) = trigexpand(sin(γ[A]-φ(t))),
	    sin(γ[B]-φ(t)) = trigexpand(sin(γ[B]-φ(t)))];
/* need to get rid of the Minus-signs .... */
assume(cos(γ[A])>0,cos(γ[B])>0,sin(γ[A])>0,sin(γ[B])>0,sin(φ(t))>0,cos(φ(t))>0);
for i:1 thru 4 do
    (trigRepl[i] : trigRepl[i] - part(rhs(trigRepl[i]),1),
     trigRepl[i] : rhs(trigRepl[i]) = lhs(trigRepl[i]),
     if is(lhs(trigRepl[i])<0) then
     	trigRepl[i] : -trigRepl[i]);
abbrev : solve([a[3]-u[3](t)=Δu[3], a[3]-u[4](t)=Δu[3]],[u[3](t),u[4](t)])[1];
collector : [[F[N1],F[N2],F[T]],[a[1],a[2],a[3]]];
tmp : makelist(makelist(coeff(coeff(rightHandS[5],collector[1][i]),collector[2][j]),j,1,3),i,1,3);
tmp : subst(trigRepl,tmp);
tmp : sum(sum(tmp[i][j]*collector[1][i]*collector[2][j],j,1,3),i,1,3);
rightHandS[5]: trigsimp(ratsimp(expand(tmp+ratsimp(trigexpand(rightHandS[5]-tmp)))));

/* ... now simplify mass matrix */
M : -subst(nuller,M);
for row:1 thru 5 do
    (for col:row thru 5 do
    	print("M(",row,",",col,") = ",M[row][col]))$

/* and print right-hand-side */
for i:1 thru length(q)  do
   (grind(trigsimp(ratsimp(rightHandS[i]))),
    print("---------------------------------------------------"))$

/* tnslate */
toDyDt : [cos(γ[A]) = cosgamma[1],cos(γ[B]) = cosgamma[2],
          sin(γ[A]) = singamma[1],sin(γ[B]) = singamma[2],
	  cos(φ(t)) = cosphi, sin(φ(t)) = sinphi, 	  
          'diff(u[3](t),t,1) = v[3],	  
          'diff(u[4](t),t,1) = v[4]]
for i:1 thru length(q)  do
   (print(trigsimp(ratsimp(subst(toDyDt,rightHandS[i])))),
    print("---------------------------------------------------"))$
/************************************************************************/
/* start vector */
starter : append(makelist('diff(u[i](t),t,1)=0,i,1,4),
   	       	 [sin(φ(t))=0,cos(φ(t))=1,'diff(φ(t),t,1)=0],
	       	 [F[N1]=0,F[N2]=0,F[T]=0, MW=0]);

atStart : makelist(subst(starter,eom)[i]=0,i,1,length(q));
TT : append(makelist(diff(u[i](t),t,2),i,1,4),['diff(φ(t),t,2),'diff(ψ(t),t,2)]);
START : solve(atStart, TT)[1];

makelist(lhs(START[i])=subst([u[3](t)=0,u[4](t)=0],rhs(START[i])),i,1,length(q));

/************************************************************************/
/* translate to first-order DGL */
toDyDt: ['diff(u[1](t),t,1) = Q[ 1],
      	 'diff(u[2](t),t,1) = Q[ 2],
      	 'diff(u[3](t),t,1) = Q[ 3],
      	 'diff(u[4](t),t,1) = Q[ 4],
      	 'diff(   φ(t),t,1) = Q[ 5],
      	 'diff(   ψ(t),t,1) = Q[ 6],
	       u[1](t) 	    = Q[ 7],
      	       u[2](t) 	    = Q[ 8],
      	       u[3](t) 	    = Q[ 9],
      	       u[4](t) 	    = Q[10],
      	       φ(t)    	    = Q[11],
      	    sin(Q[11])      = sinphi,
      	    cos(Q[11])      = cosphi];

rhside : ratsimp(subst(toDyDt,rightHandS));

for i:1 thru 6  do
   (print("rhs(",i,") = ",ratsimp(rhside[i])),
    print("---------------------------------------------------"))$


taylor : [cos(φ(t)) = 1-φ(t)^2/2!,sin(φ(t)) = φ(t)-φ(t)^3/3!];plot2d([sin(phi), phi-phi^3/3!],[phi, -%pi/2, %pi/2])$



/* velocity in contact point */
/* of axles ..... */
/* im Reference-System */
v[A] : trigsimp(diff(r[A],t));
v[B] : trigsimp(diff(r[B],t));

/* Transformation ins surface-system*/
V[a] : D[1](-γ[A]).[V[3],V[4]]+[-R*ω,0];
V[v] : D[1](-γ[B]).[V[5],V[6]];

/***************************** using formal approach ******************************/
/* in reference-coordinates */
/* axle "1" */
reverse : solve(local,κ(t))[1];
v[a] : subst([reverse, diff(reverse,t)], diff(subst(local,r[a]),t));
v[a] : subst([diff(ψ(t),t)=ω(t)], subst(subst(['diff(κ(t),t,1)=0],diff(local,t,1)), ev(v[a],nouns)));
/* in surface - coordinates */
V[a] : trigsimp(expand(D[1](-γ[A]).v[a]));

/* axle "2" */
v[b] : diff(subst(local,r[b]),t);
/* in surface - coordinates */
V[b] : trigsimp(expand(D[1](-γ[B]).v[b]));




The components of this equation are

and

Later we’ll see that this representation has a small structural fault: the wheel torque MW depends on the angular acceleration of the motor and gears. It implies that MW is a function of

and needs to be transferred to the left-hand-side of the equations. That fault will be corrected when the E-Motor and Drive-Train-components are integrated.

Variables

name symbol unit
u1 center of mass displacement in x-direction m
u2 center of mass displacement in y-direction m
u3 spring compression at front axis m
u4 spring compression at rear axis m
ϕ rotation of car-body rad
ψ rotation of wheel (absolute - not relative to car-body) rad

Parameter

name symbol value unit
axis distance a0 40 cm
distance front axis center of mass a1 10 cm
vertical distance from wheel-hub to center of mass for relaxed springs a3 10 cm
wheel radius R 58.42 mm
car-body mass mC 4 kg
wheel-set mass mW 0.3 kg
inertia-radius for body with rC 15 cm
inertia-radius wheel-set rW 4 cm
track-stiffness kT 1.00E+04 N/m
spring stiffness front k1 500 N/m
spring stiffness rear;
if "0" is given, compute it so that the static ϕ=0
k2 0 N/m
spring damping front b1 100 N/(m/s)
spring damping rear b2 100 N/(m/s)
smoothening radius for spring characteristic ε 1 mm
friction coefficient μ 0.4 1
rounding radius for friction coefficient με 0.01 1
stick coefficient μ0 0.6 1
reference velocity for damping at springs vref 5 m/s
loss velocity for rolling contact vT0 5 m/s

next workpackage: driver-controls →


References

  • ...