Dynamical Systems
Many systems in engineering can be modeled using the differential equation, known as the state equation.
x ˙ = f ( t , x , u ) \dot{x}=f(t,x,u) x ˙ = f ( t , x , u )
Symbol Description Dimension t t t Time 1 × 1 1 \times 1 1 × 1 x x x State n × 1 n \times 1 n × 1 u u u Input m × 1 m \times 1 m × 1
The output vector y is given by:
y = h ( t , x , u ) y = h(t,x,u) y = h ( t , x , u )
which comprises of variables of particular interest in the analysis of the dynamical system.
There exists variations of the state equation:
Variation Equation Description Unforced x ˙ = f ( t , x ) \dot{x}=f(t,x) x ˙ = f ( t , x ) No inputs Autonomous x ˙ = f ( x ) \dot{x}=f(x) x ˙ = f ( x ) No inputs or time dependence
Linear Mechanical Systems
Simple mechanical systems can be expressed as linear systems, where the state equation takes the very simple and special form
x ˙ = A x + B u y = C x \begin{aligned}
\dot{x}=Ax + Bu \\
y=Cx
\end{aligned} x ˙ = A x + B u y = C x
Symbol Description Dimension x x x State n x × 1 n_x \times 1 n x × 1 u u u Input n u × 1 n_u \times 1 n u × 1 y y y Output n y × 1 n_y \times 1 n y × 1 A A A State transition matrix n x × n x n_x \times n_x n x × n x B B B Input mapping matrix n x × m n_x \times m n x × m C C C Output mapping matrix n y × n x n_y \times n_x n y × n x
Non-linear Mechanical Systems
Lagrangian Dynamics
Lagrangian dynamics describe mechanical systems in terms of generalized coordinates and their derivatives
M ( q ) q ¨ + C ( q , q ˙ ) q ˙ + D ( q , q ˙ ) q ˙ + g ( q ) = G ( q ) u + J ( q ) λ M(q)\ddot{q} + C(q,\dot{q})\dot{q} +D(q,\dot{q})\dot{q} +g(q) = G(q)u +J(q)\lambda M ( q ) q ¨ + C ( q , q ˙ ) q ˙ + D ( q , q ˙ ) q ˙ + g ( q ) = G ( q ) u + J ( q ) λ
or in state representation
x ˙ = [ q ˙ q ¨ ] = [ q ˙ M − 1 ( q ) [ G ( q ) u + J ( q ) λ − C ( q , q ˙ ) q ˙ − D ( q , q ˙ ) q ˙ − g ( q ) ] ] \dot{x} = \begin{bmatrix} \dot{q} \\ \ddot{q} \end{bmatrix} =\left[\begin{array}{c} \dot{q} \\ M^{-1}(q)\left[G(q)u + J(q)\lambda - C(q, \dot{q})\dot{q} - D(q, \dot{q})\dot{q} - g(q)\right] \end{array}\right] x ˙ = [ q ˙ q ¨ ] = [ q ˙ M − 1 ( q ) [ G ( q ) u + J ( q ) λ − C ( q , q ˙ ) q ˙ − D ( q , q ˙ ) q ˙ − g ( q ) ] ]
Symbol Description Dimension Properties q q q Generalized coordinates n q × 1 n_q \times 1 n q × 1 q ˙ \dot{q} q ˙ Generalized velocity n q × 1 n_q \times 1 n q × 1 q ¨ \ddot{q} q ¨ Generalized acceleration n q × 1 n_q \times 1 n q × 1 x x x State n x × 1 n_x \times 1 n x × 1 x = [ q ; q ˙ ] x = [q; \dot{q}] x = [ q ; q ˙ ] , n x = 2 × n q n_x = 2 \times n_q n x = 2 × n q u u u Inputs n q × 1 n_q \times 1 n q × 1 y y y Outputs n q × 1 n_q \times 1 n q × 1 M ( q ) M(q) M ( q ) Mass matrix n q × n q n_q \times n_q n q × n q orthogonal C ( q , q ˙ ) C(q,\dot{q}) C ( q , q ˙ ) Coriolis matrix n q × n q n_q \times n_q n q × n q D ( q , q ˙ ) D(q,\dot{q}) D ( q , q ˙ ) Damping matrix n q × n q n_q \times n_q n q × n q g ( q ) g(q) g ( q ) Gravitational terms n q × 1 n_q \times 1 n q × 1 G ( q ) G(q) G ( q ) Input mapping matrix n q × n u n_q \times n_u n q × n u J c ( q ) J_c(q) J c ( q ) Constraint jacobian n q × n c n_q \times n_c n q × n c λ \lambda λ External forces n c × 1 n_c \times 1 n c × 1
port-Hamiltonian Dynamics
port-Hamiltonian (pH) dynamics describe mechanical systems in terms of generalized coordinates and generalized momenta
x ˙ = [ q ˙ p ˙ ] = [ 0 n q × n q I n q − I n q − D ( q , p ) ] [ ∇ q H ∇ p H ] + [ 0 n q × n u 0 n q × n c G ( q ) J ( q ) ] [ u λ ] H ( q , p ) = 1 2 p ⊤ M − 1 ( q ) p + V ( q ) \begin{aligned}
&\dot{x} = \begin{bmatrix} \dot{q} \\ \dot{p} \end{bmatrix} = \begin{bmatrix}
0_{n_q \times n_q} & I_{n_q} \\
-I_{n_q} & -D(q,p)
\end{bmatrix} \begin{bmatrix} \nabla_qH\\\nabla_pH\end{bmatrix} + \begin{bmatrix} 0_{n_q\times{n_u}} & 0_{n_q\times{n_c}} \\ G(q) & J(q) \end{bmatrix}\begin{bmatrix} u \\ \lambda \end{bmatrix} \\
&{H}(q, p)=\frac{1}{2} p^{\top} M^{-1}(q) p+V(q)
\end{aligned} x ˙ = [ q ˙ p ˙ ] = [ 0 n q × n q − I n q I n q − D ( q , p ) ] [ ∇ q H ∇ p H ] + [ 0 n q × n u G ( q ) 0 n q × n c J ( q ) ] [ u λ ] H ( q , p ) = 2 1 p ⊤ M − 1 ( q ) p + V ( q )
Symbol Description Dimension Properties q q q Generalized coordinates n q × 1 n_q \times 1 n q × 1 p p p Generalized momentum n q × 1 n_q \times 1 n q × 1 x x x State n x × 1 n_x \times 1 n x × 1 x = [ q ; p ] x = [q;p] x = [ q ; p ] u u u Inputs n u × 1 n_u \times 1 n u × 1 y y y Outputs n y × 1 n_y \times 1 n y × 1 H ( x ) H(x) H ( x ) Hamiltonian (total system energy) 1 × 1 1 \times 1 1 × 1 G ( q ) G(q) G ( q ) Input mapping matrix n q × n u n_q \times n_u n q × n u D ( q , p ) D(q,p) D ( q , p ) Damping matrix n q × n q n_q \times n_q n q × n q λ \lambda λ External forces acting n c × 1 n_c \times 1 n c × 1 J c ( q ) J_c(q) J c ( q ) Constraint jacobian n q × n c n_q \times n_c n q × n c
Consider a mechanical pH system subject to physical damping, and no external constraints, under the coordinate transformation
( q , p ) = f ( q , p ) : = ( f q ( q ) , Q T ( q ) p ) \mathbf{(q,p)} = \mathbf{f}(q,p) := (f_q(q),Q^T(q)p) ( q , p ) = f ( q , p ) := ( f q ( q ) , Q T ( q ) p )
where f q : R n q → R n q f_q : \mathbb{R}^{n_q} \rightarrow \mathbb{R}^{n_q} f q : R n q → R n q is invertible and differentiable and Q 0 ( q ) ∈ R n q × n q Q_0(q) \in \mathbb{R}^{n_q\times n_q} Q 0 ( q ) ∈ R n q × n q is full-rank for all q q q .
The pH system can be equivalently expressed as
[ q ˙ p ˙ ] = [ 0 n q × n q Q ( q ) − Q ⊤ ( q ) C ( q , p ) − D ( q , p ) ] [ ∇ q H ∇ p H ] + [ 0 G ( q ) ] u \begin{bmatrix}\mathbf{\dot{q}} \\ \mathbf{\dot{p} }\end{bmatrix} = \begin{bmatrix}
0_{n_q \times n_q} & \mathbf{Q}(q) \\
-\mathbf{Q}^\top(q) & \mathbf{C}(q,p)-\mathbf{D}(q,p)
\end{bmatrix} \begin{bmatrix} \nabla_qH\\\nabla_pH\end{bmatrix} + \begin{bmatrix} 0 \\ G(q) \end{bmatrix}u [ q ˙ p ˙ ] = [ 0 n q × n q − Q ⊤ ( q ) Q ( q ) C ( q , p ) − D ( q , p ) ] [ ∇ q H ∇ p H ] + [ 0 G ( q ) ] u
where
Q ( q ) = ∂ ∂ q ( f q ) Q 0 ∣ q = f q − 1 ( q ) D ( q , p ) = Q 0 ⊤ D Q 0 ∣ q = f q − 1 ( q ) C ( q , p ) = Q 0 ⊤ ( q ) { ∂ ⊤ ∂ q [ Q 0 − ⊤ ( q ) p ] − ∂ ∂ q [ Q 0 − ⊤ ( q ) p ] } Q 0 ( q ) ∣ q = f q − 1 ( q ) M ( q ) = Q 0 ⊤ ( q ) M ( q ) Q 0 ( q ) ∣ q = f q − 1 ( q ) G ( q ) = Q 0 ⊤ ( q ) G p ( q ) ∣ q = f q − 1 ( q ) V ( q ) = V ( q ) ∣ q = f q − 1 ( q ) . \begin{aligned}
\mathbf{Q}(\mathbf{q}) & =\left.\frac{\partial}{\partial q}\left(f_{\mathbf{q}}\right) Q_0\right|_{q=f_{\mathbf{q}}^{-1}(\mathbf{q})} \\
\mathbf{D}(\mathbf{q}, \mathbf{p}) & =\left.Q_0^{\top} D Q_0\right|_{q=f_{\mathbf{q}}^{-1}(\mathbf{q})} \\
\mathbf{C}(\mathbf{q}, \mathbf{p}) & =\left.Q_0^{\top}(q)\left\{\frac{\partial^{\top}}{\partial q}\left[Q_0^{-\top}(q) \mathbf{p}\right]-\frac{\partial}{\partial q}\left[Q_0^{-\top}(q) \mathbf{p}\right]\right\} Q_0(q)\right|_{q=f_{\mathbf{q}}^{-1}(\mathbf{q})} \\
\mathbf{M}(\mathbf{q}) & =\left.Q_0^{\top}(q) M(q) Q_0(q)\right|_{q=f_{\mathbf{q}}^{-1}(\mathbf{q})} \\
\mathbf{G}(\mathbf{q}) & =\left.Q_0^{\top}(q) G_p(q)\right|_{q=f_{\mathbf{q}}^{-1}(\mathbf{q})} \\
\mathbf{V}(\mathbf{q}) & =\left.V(q)\right|_{q=f_{\mathbf{q}}^{-1}(\mathbf{q})} .
\end{aligned} Q ( q ) D ( q , p ) C ( q , p ) M ( q ) G ( q ) V ( q ) = ∂ q ∂ ( f q ) Q 0 q = f q − 1 ( q ) = Q 0 ⊤ D Q 0 q = f q − 1 ( q ) = Q 0 ⊤ ( q ) { ∂ q ∂ ⊤ [ Q 0 − ⊤ ( q ) p ] − ∂ q ∂ [ Q 0 − ⊤ ( q ) p ] } Q 0 ( q ) q = f q − 1 ( q ) = Q 0 ⊤ ( q ) M ( q ) Q 0 ( q ) q = f q − 1 ( q ) = Q 0 ⊤ ( q ) G p ( q ) q = f q − 1 ( q ) = V ( q ) ∣ q = f q − 1 ( q ) .
Constraints
Holonomic constraints are expressed as a static relationship between configuration variables expressed as
f c ( q ) = 0 n c × 1 f_c(q) = 0_{n_c\times1} f c ( q ) = 0 n c × 1
Nonholomic constraints are expressed as a non-integrable, linear combination of generalised velocities. An important class are called nonholonomic Pfaffian constraints
J c ⊤ ( q ) q ˙ = 0 n c × 1 , J_c^{\top}(q) \dot{q}=0_{n_c \times 1}, J c ⊤ ( q ) q ˙ = 0 n c × 1 ,
Note Holonomic constraints can also be expressed as Pfaffian constraints by simply taking the time derivative
Eliminating holonomic constraints (pH)
Holonomic constraints can be eliminated from the dynamics equations of motion via the appropriate selection of generalised coordinates.
Consider the mechanical pH system with q = col ( q ^ , q ) , q ^ ∈ R n q − n c q=\operatorname{col}(\hat{q}, \mathfrak{q}), \hat{q} \in \mathbb{R}^{n_q-n_c} q = col ( q ^ , q ) , q ^ ∈ R n q − n c and q ∈ R n c \mathfrak{q} \in \mathbb{R}^{n_c} q ∈ R n c , subject to the holonomic constraint
q = f c ( q ^ ) . \mathfrak{q}=f_c(\hat{q}) . q = f c ( q ^ ) .
The system can be written in the constraint-free form
[ q ^ ˙ p ^ ˙ ] = [ 0 ( n q − n c ) × ( n q − n c ) I n q − n c − I n q − n c − D ^ ( q ^ , p ^ ) ] [ ∇ q ^ H ^ ∇ p ^ H ^ ] + [ 0 ( n q − n c ) × n u G ^ ( q ^ ) ] u y = G ^ ⊤ ( q ^ ) ∇ p ^ H ^ H ^ ( q ^ , p ^ ) = 1 2 p ^ ⊤ M ^ − 1 ( q ^ ) p ^ + V ^ ( q ^ ) , \begin{aligned}
{\left[\begin{array}{c}
\dot{\hat{q}} \\
\dot{\hat{p}}
\end{array}\right] } & =\left[\begin{array}{cc}
0_{\left(n_q-n_c\right) \times\left(n_q-n_c\right)} & I_{n_q-n_c} \\
-I_{n_q-n_c} & -\hat{D}(\hat{q}, \hat{p})
\end{array}\right]\left[\begin{array}{c}
\nabla_{\hat{q}} \hat{H} \\
\nabla_{\hat{p}} \hat{H}
\end{array}\right]+\left[\begin{array}{c}
0_{\left(n_q-n_c\right) \times n_u} \\
\hat{G}(\hat{q})
\end{array}\right] u \\
y & =\hat{G}^{\top}(\hat{q}) \nabla_{\hat{p}} \hat{H} \\
\hat{H}(\hat{q}, \hat{p}) & =\frac{1}{2} \hat{p}^{\top} \hat{M}^{-1}(\hat{q}) \hat{p}+\hat{V}(\hat{q}),
\end{aligned} [ q ^ ˙ p ^ ˙ ] y H ^ ( q ^ , p ^ ) = [ 0 ( n q − n c ) × ( n q − n c ) − I n q − n c I n q − n c − D ^ ( q ^ , p ^ ) ] [ ∇ q ^ H ^ ∇ p ^ H ^ ] + [ 0 ( n q − n c ) × n u G ^ ( q ^ ) ] u = G ^ ⊤ ( q ^ ) ∇ p ^ H ^ = 2 1 p ^ ⊤ M ^ − 1 ( q ^ ) p ^ + V ^ ( q ^ ) ,
where
p ^ ( q ^ , p ) = [ I n q − n c ∂ ⊤ f c ∂ q ^ ] p ∣ q = f c ( q ^ ) M ^ ( q ^ ) = [ I n q − n c ∂ ⊤ f c ∂ q ^ ] M ∣ q = f c ( q ^ ) [ I n q − n c ∂ f c ∂ q ^ ] D ^ ( q ^ , p ^ ) = [ I n q − n c ∂ ⊤ f c ∂ q ^ ] D ∣ q = f c ( q ^ ) [ I n q − n c ∂ f c ∂ q ^ ] G ^ ( q ^ ) = [ I n q − n c ∂ ⊤ f c ∂ q ^ ] G p ∣ q = f c ( q ^ ) . \begin{aligned}
\hat{p}(\hat{q}, p) & =\left.\left[\begin{array}{ll}
I_{n_q-n_c} & \frac{\partial^{\top} f_c}{\partial \hat{q}}
\end{array}\right] p\right|_{\mathfrak{q}=f_c(\hat{q})} \\
\hat{M}(\hat{q}) & =\left.\left[\begin{array}{ll}
I_{n_q-n_c} & \frac{\partial^{\top} f_c}{\partial \hat{q}}
\end{array}\right] M\right|_{\mathfrak{q}=f_c(\hat{q})}\left[\begin{array}{c}
I_{n_q-n_c} \\
\frac{\partial f_c}{\partial \hat{q}}
\end{array}\right] \\
\hat{D}(\hat{q}, \hat{p}) & =\left.\left[\begin{array}{ll}
I_{n_q-n_c} & \frac{\partial^{\top} f_c}{\partial \hat{q}}
\end{array}\right] D\right|_{\mathfrak{q}=f_c(\hat{q})}\left[\begin{array}{c}
I_{n_q-n_c} \\
\frac{\partial f_c}{\partial \hat{q}}
\end{array}\right] \\
\hat{G}(\hat{q}) & =\left.\left[\begin{array}{ll}
I_{n_q-n_c} & \frac{\partial^{\top} f_c}{\partial \hat{q}}
\end{array}\right] G_p\right|_{\mathfrak{q}=f_c(\hat{q})} .
\end{aligned} p ^ ( q ^ , p ) M ^ ( q ^ ) D ^ ( q ^ , p ^ ) G ^ ( q ^ ) = [ I n q − n c ∂ q ^ ∂ ⊤ f c ] p q = f c ( q ^ ) = [ I n q − n c ∂ q ^ ∂ ⊤ f c ] M q = f c ( q ^ ) [ I n q − n c ∂ q ^ ∂ f c ] = [ I n q − n c ∂ q ^ ∂ ⊤ f c ] D q = f c ( q ^ ) [ I n q − n c ∂ q ^ ∂ f c ] = [ I n q − n c ∂ q ^ ∂ ⊤ f c ] G p q = f c ( q ^ ) .
Eliminating nonholonomic constraints (pH)
Nonholonomic constraints can be elimiated from a pH mechanical system by applying the momentum transform
p ~ = [ μ s p r ] = [ J c ⊤ ( q ) J c ⊥ ( q ) ] ⏟ : = Q ( q ) p 0 \tilde{p}=\left[\begin{array}{c}
\mu_s \\
p_r
\end{array}\right]=\underbrace{\left[\begin{array}{c}
J_c^{\top}(q) \\
J_c^{\perp}(q)
\end{array}\right]}_{:=Q(q)} p_0 p ~ = [ μ s p r ] = := Q ( q ) [ J c ⊤ ( q ) J c ⊥ ( q ) ] p 0
obtaining reduced-order model
[ q ˙ p ˙ s ] = [ 0 n J c ⊥ ⊤ ( q ) − J c ⊥ ( q ) C s ( p r , q ) ] [ ∇ q H r ∇ p r H r ] + [ 0 n × m G s ( q ) ] u H r ( p r , q ) = 1 2 p r ⊤ M s − 1 ( q ) p r + V ( q ) , \begin{aligned}
\begin{bmatrix}
\dot{q} \\
\dot{p}_s
\end{bmatrix}
=&
\left[\begin{array}{cc}
0_n & J_c^{\perp\top}(q) \\
-J_c^{\perp}(q)& C_s(p_r, q)
\end{array}\right]
\left[\begin{array}{c}
\nabla_q H_r \\
\nabla_{p_r} H_r
\end{array}\right] +
\left[\begin{array}{c}
0_{n \times m} \\
G_s(q)
\end{array}\right] u\\
&H_r(p_r, q) =\frac{1}{2} p_r^{\top} M_s^{-1}(q) p_r+\mathcal{V}(q),
\end{aligned} [ q ˙ p ˙ s ] = [ 0 n − J c ⊥ ( q ) J c ⊥ ⊤ ( q ) C s ( p r , q ) ] [ ∇ q H r ∇ p r H r ] + [ 0 n × m G s ( q ) ] u H r ( p r , q ) = 2 1 p r ⊤ M s − 1 ( q ) p r + V ( q ) ,
where
G s ( q ) = J c ⊥ ( q ) G 0 ( q ) C s ( p r , q ) = J c ⊥ ( q ) { ∂ ⊤ ∂ q [ M 0 ( q ) J c ⊥ ⊤ ( q ) M s − 1 ( q ) p r ] − ∂ ∂ q [ M 0 ( q ) J c ⊥ ⊤ ( q ) M s − 1 ( q ) p r ] } J c ⊥ ⊤ ( q ) − J c ⊥ ( q ) D 0 ( q , p 0 ) J c ⊥ ⊤ ( q ) M s ( q ) = J c ⊥ ( q ) M 0 ( q ) J c ⊥ ⊤ ( q ) \begin{aligned}
G_s(q) & =J_c^{\perp}(q) G_0(q)\\
C_s(p_r, q) & =J_c^{\perp}(q)\left\{\frac{\partial^{\top}}{\partial q}\left[M_0(q) J_c^{\perp\top}(q)M_s^{-1}(q) p_r\right]\right. \\
& \left.\quad-\frac{\partial}{\partial q}\left[M_0(q) J_c^{\perp\top}(q) M_s^{-1}(q) p_r\right]\right\} J_c^{\perp\top}(q) \\&- J_c^{\perp}(q) D_0\left(q, p_0\right) J_c^{\perp\top}(q) \\
M_s(q) & =J_c^{\perp}(q) M_0(q) J_c^{\perp\top}(q)
\end{aligned} G s ( q ) C s ( p r , q ) M s ( q ) = J c ⊥ ( q ) G 0 ( q ) = J c ⊥ ( q ) { ∂ q ∂ ⊤ [ M 0 ( q ) J c ⊥ ⊤ ( q ) M s − 1 ( q ) p r ] − ∂ q ∂ [ M 0 ( q ) J c ⊥ ⊤ ( q ) M s − 1 ( q ) p r ] } J c ⊥ ⊤ ( q ) − J c ⊥ ( q ) D 0 ( q , p 0 ) J c ⊥ ⊤ ( q ) = J c ⊥ ( q ) M 0 ( q ) J c ⊥ ⊤ ( q )
Note Generalized momentum vector p p p can be recovered by the expression
p = M 0 ( q ) J c ⊥ ⊤ ( q ) M s − 1 ( q ) p r . p = M_0(q)J_c^{\perp\top}(q)M_s^{-1}(q)p_r. p = M 0 ( q ) J c ⊥ ⊤ ( q ) M s − 1 ( q ) p r .
Eliminating nonholonomic constraints (Lagrangian)
Let us begin with the widely used Lagrange-d'Alembert equations
d d t ( ∂ L ∂ q ˙ ) T − ( ∂ L ∂ q ) T = F ext + J c λ , \frac{\mathrm{d}}{\mathrm{d} t}\left(\frac{\partial L}{\partial \dot{{q}}}\right)^{\mathrm{T}}-\left(\frac{\partial L}{\partial {q}}\right)^{\mathrm{T}}={F}_{\text {ext }}+ J_c{\lambda}, d t d ( ∂ q ˙ ∂ L ) T − ( ∂ q ∂ L ) T = F ext + J c λ ,
which describe the dynamics of systems subject to k k k nonholonomic (Pfaffian) constraints of the form
J c ⊤ q ˙ = 0. J_c^\top \dot{{q}}={0} . J c ⊤ q ˙ = 0 .
The matrix form of is given as
M ( q ) q ¨ + C ( q ) q ˙ + g ( q ) = G ( q ) u + J c λ {M}(q) \ddot{{q}}+{C}(q) \dot{{q}}+g(q)=G(q)u+ J_c\lambda M ( q ) q ¨ + C ( q ) q ˙ + g ( q ) = G ( q ) u + J c λ
Due to the nonholonomic constraints, the admissible velocitie must be of the form
q ˙ = S q ˙ r \dot{q} = S\dot{q}_r q ˙ = S q ˙ r
M q r ˙ + C q r + S T ∇ q V = τ + J q r {M} \dot{q_r}+{C} q_r+{S}^{\mathrm{T}} \nabla_{{q}} V=\boldsymbol{\tau}+{J} q_r M q r ˙ + C q r + S T ∇ q V = τ + J q r