Update Content - 2021-02-01

This commit is contained in:
Thomas Dehaeze 2021-02-01 16:00:24 +01:00
parent bdf6920eef
commit b01a76e8ab

View File

@ -8,7 +8,7 @@ Tags
: [Stewart Platforms]({{< relref "stewart_platforms" >}}), [Reference Books]({{< relref "reference_books" >}})
Reference
: ([Taghirad 2013](#orgf8aae74))
: ([Taghirad 2013](#org8f0ac84))
Author(s)
: Taghirad, H.
@ -22,7 +22,7 @@ PDF version
## Introduction {#introduction}
<a id="org65cfcae"></a>
<a id="org8ef73b4"></a>
This book is intended to give some analysis and design tools for the increase number of engineers and researchers who are interested in the design and implementation of parallel robots.
A systematic approach is presented to analyze the kinematics, dynamics and control of parallel robots.
@ -47,7 +47,7 @@ The control of parallel robots is elaborated in the last two chapters, in which
## Motion Representation {#motion-representation}
<a id="orgd721dfb"></a>
<a id="org17f7d3c"></a>
### Spatial Motion Representation {#spatial-motion-representation}
@ -62,7 +62,7 @@ Let us define:
The absolute position of point \\(P\\) of the rigid body can be constructed from the relative position of that point with respect to the moving frame \\(\\{\bm{B}\\}\\), and the **position and orientation** of the moving frame \\(\\{\bm{B}\\}\\) with respect to the fixed frame \\(\\{\bm{A}\\}\\).
<a id="orgfdbabd1"></a>
<a id="orge0ac275"></a>
{{< figure src="/ox-hugo/taghirad13_rigid_body_motion.png" caption="Figure 1: Representation of a rigid body spatial motion" >}}
@ -87,12 +87,12 @@ It can be **represented in several different ways**: the rotation matrix, the sc
##### Rotation Matrix {#rotation-matrix}
We consider a rigid body that has been exposed to a pure rotation.
Its orientation has changed from a state represented by frame \\(\\{\bm{A}\\}\\) to its current orientation represented by frame \\(\\{\bm{B}\\}\\) (Figure [2](#orga66f90a)).
Its orientation has changed from a state represented by frame \\(\\{\bm{A}\\}\\) to its current orientation represented by frame \\(\\{\bm{B}\\}\\) (Figure [2](#org05b070b)).
A \\(3 \times 3\\) rotation matrix \\({}^A\bm{R}\_B\\) is defined by
\begin{equation}
\tcmbox{{}^A\bm{R}\_B = \left[ {}^A\hat{\bm{x}}\_B | {}^A\hat{\bm{y}}\_B | {}^A\hat{\bm{z}}\_B \right] = \begin{bmatrix}
\boxed{{}^A\bm{R}\_B = \left[ {}^A\hat{\bm{x}}\_B | {}^A\hat{\bm{y}}\_B | {}^A\hat{\bm{z}}\_B \right] = \begin{bmatrix}
u\_{x} & v\_{x} & z\_{x} \\\\\\
u\_{y} & v\_{y} & z\_{y} \\\\\\
u\_{z} & v\_{z} & z\_{z}
@ -109,7 +109,7 @@ in which \\({}^A\hat{\bm{x}}\_B, {}^A\hat{\bm{y}}\_B\\) and \\({}^A\hat{\bm{z}}\
The nine elements of the rotation matrix can be simply represented as the projections of the Cartesian unit vectors of frame \\(\\{\bm{B}\\}\\) on the unit vectors of frame \\(\\{\bm{A}\\}\\).
<a id="orga66f90a"></a>
<a id="org05b070b"></a>
{{< figure src="/ox-hugo/taghirad13_rotation_matrix.png" caption="Figure 2: Pure rotation of a rigid body" >}}
@ -119,7 +119,7 @@ The rotation matrix has a number of properties linking each of its nine elements
- **Transposition**: \\({}^B\bm{R}\_A = {}^A\bm{R}\_B^{T}\\)
- **Inverse**: \\({}^B\bm{R}\_A = {}^A\bm{R}\_B^{-1} = {}^A\bm{R}\_B^{T}\\)
- **Pure Rotation Mapping**: Suppose that the point of a rigid body with respect to the moving frame \\(\\{\bm{B}\\}\\) is given and denoted by \\({}^B\bm{P}\\) and we wish to express the position of this point with respect to the fixed frame \\(\\{\bm{A}\\}\\). Consider that the rigid body has been exposed to a pure rotation (\\(\\{\bm{A}\\}\\) and \\(\\{\bm{B}\\}\\) are coincident at their origins). Then
\\[ \tcmbox{{}^A\bm{P} = {}^A\bm{R}\_B {}^B\bm{P}} \\]
\\[ \boxed{{}^A\bm{P} = {}^A\bm{R}\_B {}^B\bm{P}} \\]
- **Determinant**: \\(\det({}^A\bm{R}\_B) = 1\\)
- **Eigenvalues**: The eigenvalues of a rotation matrix \\({}^A\bm{R}\_B\\) are equal to \\(1\\), \\(e^{i\theta}\\) and \\(e^{-i\theta}\\) where \\(\theta\\) is calculated from \\(\theta = \cos^{-1}\frac{\text{tr}({}^A\bm{R}\_B) - 1}{2}\\).
@ -135,14 +135,14 @@ The term screw axis for this axis of rotation has the benefit that a general mot
The screw axis representation has the benefit of **using only four parameters** to describe a pure rotation.
These parameters are the angle of rotation \\(\theta\\) and the axis of rotation which is a unit vector \\({}^A\hat{\bm{s}} = [s\_x, s\_y, s\_z]^T\\).
<a id="org37e51c1"></a>
<a id="org4350510"></a>
{{< figure src="/ox-hugo/taghirad13_screw_axis_representation.png" caption="Figure 3: Pure rotation about a screw axis" >}}
The Rodrigue's rotation formula for spatial rotation of a rigid body gives us the new position \\(\bm{P}\_2\\) of point \\(\bm{P}\_1\\) after a rotation represented by the screw axis \\(\hat{\bm{s}}\\) and the angle \\(\theta\\):
\begin{equation}
\tcmbox{\bm{P}\_2 = \bm{P}\_1 \cos \theta + (\hat{\bm{s}} \times \bm{P}\_1)\sin\theta + (\bm{P}\_1 \cdot \hat{\bm{s}})\hat{\bm{s}}}
\boxed{\bm{P}\_2 = \bm{P}\_1 \cos \theta + (\hat{\bm{s}} \times \bm{P}\_1)\sin\theta + (\bm{P}\_1 \cdot \hat{\bm{s}})\hat{\bm{s}}}
\end{equation}
@ -161,12 +161,12 @@ Three other types of Euler angles are consider with respect to a moving frame: t
The pitch, roll and yaw angles are defined for a moving object in space as the rotations along the lateral, longitudinal and vertical axes attached to the moving object.
<a id="org358005b"></a>
<a id="orge6691ca"></a>
{{< figure src="/ox-hugo/taghirad13_pitch-roll-yaw.png" caption="Figure 4: Definition of pitch, roll and yaw angles on an air plain" >}}
Since all three rotations take place about the axes of a **fixed coordinate frame**, the resulting rotation matrix is obtained by multiplying the three basic rotation matrices as follows:
\\[ \tcmbox{\bm{R}\_{PRY}(\alpha, \beta, \gamma) = \bm{R}\_z(\gamma) \bm{R}\_y(\beta) \bm{R}\_x(\alpha)} \\]
\\[ \boxed{\bm{R}\_{PRY}(\alpha, \beta, \gamma) = \bm{R}\_z(\gamma) \bm{R}\_y(\beta) \bm{R}\_x(\alpha)} \\]
To go from rotation matrix to Pitch-Roll-Yaw angles, the following set of equations can be used:
@ -266,7 +266,7 @@ If the pose of a rigid body \\(\\{{}^A\bm{R}\_B, {}^A\bm{P}\_{O\_B}\\}\\) is giv
To describe general transformations, we introduce the \\(4\times1\\) **homogeneous coordinates**, and Eq. \eqref{eq:chasles_therorem} is generalized to
\begin{equation}
\tcmbox{{}^A\bm{P} = {}^A\bm{T}\_B {}^B\bm{P}}
\boxed{{}^A\bm{P} = {}^A\bm{T}\_B {}^B\bm{P}}
\end{equation}
in which \\({}^A\bm{T}\_B\\) is a \\(4\times4\\) **homogeneous transformation matrix**.
@ -284,14 +284,14 @@ For line vectors, both orientation and translation of the moving frame contribut
Homogeneous coordinate of such vectors is generated by appending \\(1\\) to the three components of that vector:
\begin{equation}
\tcmbox{\bm{V} = \begin{bmatrix} v\_x \\ v\_y \\ v\_z \\ 1 \end{bmatrix}}
\boxed{\bm{V} = \begin{bmatrix} v\_x \\ v\_y \\ v\_z \\ 1 \end{bmatrix}}
\end{equation}
For free vectors, only the orientation of the moving frame contributes to their value.
The homogeneous coordinate is then
\begin{equation}
\tcmbox{\bm{\omega} = \begin{bmatrix} \omega\_x \\ \omega\_y \\ \omega\_z \\ 0 \end{bmatrix}}
\boxed{\bm{\omega} = \begin{bmatrix} \omega\_x \\ \omega\_y \\ \omega\_z \\ 0 \end{bmatrix}}
\end{equation}
@ -366,7 +366,7 @@ There exist transformations to from screw displacement notation to the transform
Let us consider the motion of a rigid body described at three locations (Figure [fig:consecutive_transformations](#fig:consecutive_transformations)).
Frame \\(\\{\bm{A}\\}\\) represents the initial location, frame \\(\\{\bm{B}\\}\\) is an intermediate location, and frame \\(\\{\bm{C}\\}\\) represents the rigid body at its final location.
<a id="orgd301fdc"></a>
<a id="org79cb54b"></a>
{{< figure src="/ox-hugo/taghirad13_consecutive_transformations.png" caption="Figure 5: Motion of a rigid body represented at three locations by frame \\(\\{\bm{A}\\}\\), \\(\\{\bm{B}\\}\\) and \\(\\{\bm{C}\\}\\)" >}}
@ -383,7 +383,7 @@ And we have:
From which, the consecutive transformation can be defined as follows:
\begin{equation}
\tcmbox{{}^A\bm{T}\_C = {}^A\bm{T}\_B {}^B\bm{T}\_C}
\boxed{{}^A\bm{T}\_C = {}^A\bm{T}\_B {}^B\bm{T}\_C}
\end{equation}
@ -429,7 +429,7 @@ Hence, the **inverse of the transformation matrix** can be obtain by
## Kinematics {#kinematics}
<a id="org6add649"></a>
<a id="orgfb1e6d5"></a>
### Introduction {#introduction}
@ -536,7 +536,7 @@ The position of the point \\(O\_B\\) of the moving platform is described by the
\end{bmatrix}
\end{equation}
<a id="orgf798a71"></a>
<a id="orgd8f574a"></a>
{{< figure src="/ox-hugo/taghirad13_stewart_schematic.png" caption="Figure 6: Geometry of a Stewart-Gough platform" >}}
@ -589,7 +589,7 @@ The complexity of the problem depends widely on the manipulator architecture and
## Jacobian: Velocities and Static Forces {#jacobian-velocities-and-static-forces}
<a id="org5fd1ad8"></a>
<a id="org3ec674f"></a>
### Introduction {#introduction}
@ -631,7 +631,7 @@ The direction of \\(\bm{\Omega}\\) indicates the instantaneous axis of rotation
The angular velocity vector is related to the screw formalism by equation \eqref{eq:angular_velocity_vector}.
\begin{equation}
\tcmbox{\bm{\Omega} \triangleq \dot{\theta} \hat{\bm{s}}}
\boxed{\bm{\Omega} \triangleq \dot{\theta} \hat{\bm{s}}}
\end{equation}
The angular velocity can be expressed in any frame. For example \\({}^A\bm{\Omega}\\) denotes the angular velocity of the rigid body expressed in the frame \\(\\{\bm{A}\\}\\) and we have:
@ -671,13 +671,13 @@ in which \\(\bm{\Omega}\\) denotes the angular velocity of the moving frame with
The term \\(\bm{\Omega}\times(\cdot)\\) can be written in matrix form:
\begin{equation}
\tcmbox{\left( \dv{(\cdot)}{t} \right)\_{\text{fix}} = \left( \pdv{(\cdot)}{t} \right)\_{\text{mov}} + \bm{\Omega}^\times(\cdot)}
\boxed{\left( \dv{(\cdot)}{t} \right)\_{\text{fix}} = \left( \pdv{(\cdot)}{t} \right)\_{\text{mov}} + \bm{\Omega}^\times(\cdot)}
\end{equation}
The matrix \\(\bm{\Omega}^\times\\) denotes a **skew-symmetric matrix** defined by:
\begin{equation}
\tcmbox{\bm{\Omega}^\times = \begin{bmatrix}
\boxed{\bm{\Omega}^\times = \begin{bmatrix}
0 & -\Omega\_z & \Omega\_y \\\\\\
\Omega\_z & 0 & -\Omega\_x \\\\\\
-\Omega\_y & \Omega\_x & 0
@ -686,7 +686,7 @@ The matrix \\(\bm{\Omega}^\times\\) denotes a **skew-symmetric matrix** defined
Now consider the general motion of a rigid body shown in Figure [fig:general_motion](#fig:general_motion), in which a moving frame \\(\\{\bm{B}\\}\\) is attached to the rigid body and **the problem is to find the absolute velocity** of point \\(P\\) with respect to a fixed frame \\(\\{\bm{A}\\}\\).
<a id="orgad9c345"></a>
<a id="org998d8f2"></a>
{{< figure src="/ox-hugo/taghirad13_general_motion.png" caption="Figure 7: Instantaneous velocity of a point \\(P\\) with respect to a moving frame \\(\\{\bm{B}\\}\\)" >}}
@ -700,7 +700,7 @@ To derive the velocity of point \\(P\\), we differentiate with respect to time:
The time derivative of the rotation matrix \\({}^A\dot{\bm{R}}\_B\\) is:
\begin{equation}
\tcmbox{{}^A\dot{\bm{R}}\_B = {}^A\bm{\Omega}^\times \ {}^A\bm{R}\_B}
\boxed{{}^A\dot{\bm{R}}\_B = {}^A\bm{\Omega}^\times \ {}^A\bm{R}\_B}
\end{equation}
And we finally obtain equation \eqref{eq:absolute_velocity_formula}.
@ -745,7 +745,7 @@ Generally \\(m \geq n\\), in which for a fully parallel manipulator \\(m=n\\) an
We can differentiate this equation with respect to time and obtain:
\begin{equation}
\tcmbox{\bm{J}\_x \dot{\bm{\mathcal{X}}} = \bm{J}\_q \dot{\bm{q}}}
\boxed{\bm{J}\_x \dot{\bm{\mathcal{X}}} = \bm{J}\_q \dot{\bm{q}}}
\end{equation}
where
@ -791,7 +791,7 @@ with
By taking the time derivative, we obtain the following **Velocity Loop Closure**:
\begin{equation}
\tcmbox{\dot{\bm{p}} = \dot{\bm{d}\_i} - \bm{\omega} \times \bm{R} \bm{b}\_i \quad \text{for}\ i = 1, \ldots, m}
\boxed{\dot{\bm{p}} = \dot{\bm{d}\_i} - \bm{\omega} \times \bm{R} \bm{b}\_i \quad \text{for}\ i = 1, \ldots, m}
\end{equation}
@ -859,7 +859,7 @@ By dot multiply both side of the equation by \\(\hat{\bm{s}}\_i\\):
We then omit the superscript \\(A\\) and we can rearrange the 6 equations into a matrix form
\begin{equation}
\tcmbox{\dot{\bm{\mathcal{L}}} = \bm{J} \dot{\bm{\mathcal{X}}}}
\boxed{\dot{\bm{\mathcal{L}}} = \bm{J} \dot{\bm{\mathcal{X}}}}
\end{equation}
<div class="cbox">
@ -920,7 +920,7 @@ We assume that the frictional forces acting on the joints are negligible, and al
The principle of virtual work states that the total virtual work, \\(\delta W\\), done by all actuators and external forces is equal to zero:
\begin{equation}
\tcmbox{\delta W = \bm{\tau}^T \delta \bm{q} - \bm{\mathcal{F}}^T \delta \bm{\mathcal{X}} = 0}
\boxed{\delta W = \bm{\tau}^T \delta \bm{q} - \bm{\mathcal{F}}^T \delta \bm{\mathcal{X}} = 0}
\end{equation}
Furthermore, from the definition of the Jacobian, the virtual displacements \\(\delta \bm{q}\\) and \\(\delta \bm{\mathcal{X}}\\) are related by the Jacobian:
@ -945,7 +945,7 @@ We obtain that the **Jacobian matrix** constructs the **transformation needed to
As shown in Figure [fig:stewart_static_forces](#fig:stewart_static_forces), the twist of moving platform is described by a 6D vector \\(\dot{\bm{\mathcal{X}}} = \left[ {}^A\bm{v}\_P \ {}^A\bm{\omega} \right]^T\\), in which \\({}^A\bm{v}\_P\\) is the velocity of point \\(O\_B\\), and \\({}^A\bm{\omega}\\) is the angular velocity of moving platform.<br />
<a id="org03959f7"></a>
<a id="orge814277"></a>
{{< figure src="/ox-hugo/taghirad13_stewart_static_forces.png" caption="Figure 8: Free-body diagram of forces and moments action on the moving platform and each limb of the Stewart-Gough platform" >}}
@ -986,7 +986,7 @@ Writing the two equations together in a matrix form results in
There we can recognize the transpose of the Jacobian matrix:
\begin{equation}
\tcmbox{\bm{\mathcal{F}} = \bm{J}^T \bm{\tau}}
\boxed{\bm{\mathcal{F}} = \bm{J}^T \bm{\tau}}
\end{equation}
in which \\(\bm{\tau} = [f\_1, f\_2, \cdots, f\_6]^T\\) is the vector of actuator forces, and \\(\bm{\mathcal{F}} = [\bm{f}, \bm{n}]^T\\) is the 6D wrench applied by the manipulator to the environment.
@ -1004,7 +1004,7 @@ Thus, the stiffness of a manipulator has a direct impact on its overall position
The relation between the applied actuator force \\(\tau\_i\\) and the corresponding small deflection \\(\Delta q\_i\\) along the applied force axis can be approximated as a **linear function**:
\begin{equation}
\tcmbox{\tau\_i = k\_i \cdot \Delta q\_i}
\boxed{\tau\_i = k\_i \cdot \Delta q\_i}
\end{equation}
in which \\(k\_i\\) denotes the **stiffness constant of the actuator**.<br />
@ -1012,7 +1012,7 @@ in which \\(k\_i\\) denotes the **stiffness constant of the actuator**.<br />
Re-writing the equation \eqref{eq:stiffness_actuator} for all limbs in a matrix form result in
\begin{equation}
\tcmbox{\bm{\tau} = \mathcal{K} \cdot \Delta \bm{q}}
\boxed{\bm{\tau} = \mathcal{K} \cdot \Delta \bm{q}}
\end{equation}
in which \\(\bm{\tau}\\) is the vector of actuator forces, and \\(\Delta \bm{q}\\) corresponds to the actuator deflections.
@ -1035,7 +1035,7 @@ Furthermore, rewriting the Jacobian as the projection of actuator forces to the
Hence, by substituting \eqref{eq:stiffness_matrix_relation} and \eqref{eq:jacobian_disp_inf} in \eqref{eq:jacobian_force_inf}, we obtain:
\begin{equation}
\tcmbox{\bm{\mathcal{F}} = \underbrace{\bm{J}^T \mathcal{K} \bm{J}}\_{\bm{K}} \cdot \Delta \bm{\mathcal{X}}}
\boxed{\bm{\mathcal{F}} = \underbrace{\bm{J}^T \mathcal{K} \bm{J}}\_{\bm{K}} \cdot \Delta \bm{\mathcal{X}}}
\end{equation}
Equation \eqref{eq:stiffness_jacobian} implies that the moving platform output wrench is related to its deflection by the **stiffness matrix** \\(K\\).
@ -1057,7 +1057,7 @@ The stiffness matrix has desirable characteristics for analysis:
If the stiffness matrix is inversible (\\(\det( \bm{J}^T \bm{J}) \ne 0\\)), the **compliance matrix** of the manipulator is defined as
\begin{equation}
\tcmbox{\bm{C} = \bm{K}^{-1} = (\bm{J}^T \mathcal{K} \bm{J})^{-1}}
\boxed{\bm{C} = \bm{K}^{-1} = (\bm{J}^T \mathcal{K} \bm{J})^{-1}}
\end{equation}
The compliance matrix of a manipulator shows the mapping of the moving platform wrench to its deflection by
@ -1102,7 +1102,7 @@ in which \\(\sigma\_{\text{min}}\\) and \\(\sigma\_{\text{max}}\\) are the small
In this section, we restrict our analysis to a 3-6 structure (Figure [fig:stewart36](#fig:stewart36)) in which there exist six distinct attachment points \\(A\_i\\) on the fixed base and three moving attachment point \\(B\_i\\).
<a id="orga01f67c"></a>
<a id="org9d3d43b"></a>
{{< figure src="/ox-hugo/taghirad13_stewart36.png" caption="Figure 9: Schematic of a 3-6 Stewart-Gough platform" >}}
@ -1132,7 +1132,7 @@ The largest axis of the stiffness transformation hyper-ellipsoid is given by thi
## Dynamics {#dynamics}
<a id="org647b848"></a>
<a id="org21126fb"></a>
### Introduction {#introduction}
@ -1162,7 +1162,7 @@ The first item is the main advantage of the Newton-Euler formulation, the second
The dynamic equations in an **explicit form** can be written as:
\begin{equation}
\tcmbox{\bm{M}(\bm{\mathcal{X}}) \ddot{\bm{\mathcal{X}}} + \bm{C}(\bm{\mathcal{X}}, \dot{\bm{\mathcal{X}}}) \dot{\bm{\mathcal{X}}} + \bm{G}(\bm{\mathcal{X}}) = \bm{\mathcal{F}}}
\boxed{\bm{M}(\bm{\mathcal{X}}) \ddot{\bm{\mathcal{X}}} + \bm{C}(\bm{\mathcal{X}}, \dot{\bm{\mathcal{X}}}) \dot{\bm{\mathcal{X}}} + \bm{G}(\bm{\mathcal{X}}) = \bm{\mathcal{F}}}
\end{equation}
in which:
@ -1263,7 +1263,7 @@ For the case where \\(P\\) is a point embedded in the rigid body, \\({}^B\bm{v}\
In this section, the properties of mass, namely **center of mass**, **moments of inertia** and its characteristics and the required transformations are described.
<a id="org4083afe"></a>
<a id="org9820ce5"></a>
{{< figure src="/ox-hugo/taghirad13_mass_property_rigid_body.png" caption="Figure 10: Mass properties of a rigid body" >}}
@ -1338,7 +1338,7 @@ Consider frame \\(\\{\bm{C}\\}\\) **parallel** to \\(\\{\bm{A}\\}\\) and attache
The relation between the inertia matrix about \\(A\\) and that about \\(C\\) is given by the following relation:
\begin{equation}
\tcmbox{{}^A\bm{I} = {}^C\bm{I} + m(\bm{p}\_c^T \bm{p}\_c \bm{I}\_{3 \times 3} - \bm{p}\_c \bm{p}\_c^T)}
\boxed{{}^A\bm{I} = {}^C\bm{I} + m(\bm{p}\_c^T \bm{p}\_c \bm{I}\_{3 \times 3} - \bm{p}\_c \bm{p}\_c^T)}
\end{equation}
in which \\(m\\) denotes the mass of the rigid body and \\(\bm{I}\_{3 \times 3}\\) denotes the identity matrix.<br />
@ -1369,7 +1369,7 @@ And because \\(\int\_V r \rho dV = 0\\), we have by substitution
and thus
\begin{equation}
\tcmbox{{}^A\bm{G} = m \cdot {}^A\bm{v}\_C}
\boxed{{}^A\bm{G} = m \cdot {}^A\bm{v}\_C}
\end{equation}
in which \\({}^A\bm{v}\_C\\) denotes the velocity of the center of mass with respect to the frame \\(\\{\bm{A}\\}\\).<br />
@ -1377,7 +1377,7 @@ in which \\({}^A\bm{v}\_C\\) denotes the velocity of the center of mass with res
This result implies that the **total linear momentum** of differential masses is equal to the linear momentum of a **point mass** \\(m\\) located at the **center of mass**.
This highlights the important of the center of mass in dynamic formulation of rigid bodies.
<a id="org6e26879"></a>
<a id="org0520561"></a>
{{< figure src="/ox-hugo/taghirad13_angular_momentum_rigid_body.png" caption="Figure 11: The components of the angular momentum of a rigid body about \\(A\\)" >}}
@ -1395,7 +1395,7 @@ By substituting \\(\bm{p} = \bm{p}\_c + \bm{r}\\) in the previous equations, be
Therefore, angular momentum of the rigid body about point \\(A\\) is reduced to
\begin{equation}
\tcmbox{{}^A\bm{H} = \bm{p}\_c \times \bm{G}\_c + {}^C\bm{H}}
\boxed{{}^A\bm{H} = \bm{p}\_c \times \bm{G}\_c + {}^C\bm{H}}
\end{equation}
in which
@ -1412,7 +1412,7 @@ If the center of mass is taken as the reference point, the relation describing a
The Kinetic energy of a rigid body is defined as
\begin{equation}
\tcmbox{\bm{K} = \frac{1}{2} \int\_V \bm{v} \cdot \bm{v} \rho dV}
\boxed{\bm{K} = \frac{1}{2} \int\_V \bm{v} \cdot \bm{v} \rho dV}
\end{equation}
The velocity of a differential mass \\(\rho dV\\) can be represented by linear velocity of the center of mass and angular velocity of the rigid body as
@ -1421,7 +1421,7 @@ The velocity of a differential mass \\(\rho dV\\) can be represented by linear v
By substitution, the kinetic energy of the rigid body may be obtained by:
\begin{equation}
\tcmbox{\bm{K} = \frac{1}{2} \bm{v}\_c \times \bm{G}\_c + \frac{1}{2} \bm{\Omega} \cdot {}^C\bm{H}}
\boxed{\bm{K} = \frac{1}{2} \bm{v}\_c \times \bm{G}\_c + \frac{1}{2} \bm{\Omega} \cdot {}^C\bm{H}}
\end{equation}
in which \\(\bm{G}\_C\\) is the linear momentum of the rigid body and \\({}^C\bm{H}\\) is the angular momentum of the rigid body about the center of mass.<br />
@ -1522,7 +1522,7 @@ The position vector of these two center of masses can be determined by the follo
\bm{p}\_{i\_2} &= \bm{a}\_{i} + ( l\_i - c\_{i\_2}) \hat{\bm{s}}\_{i}
\end{align}
<a id="orgefff9ac"></a>
<a id="orgd4e4f57"></a>
{{< figure src="/ox-hugo/taghirad13_free_body_diagram_stewart.png" caption="Figure 12: Free-body diagram of the limbs and the moving platform of a general Stewart-Gough manipulator" >}}
@ -1671,7 +1671,7 @@ in which \\(\bm{\mathcal{X}}\\) consists of six coordinates: the first three \\(
It is preferable to use the **screw coordinates** for representing the angular motion **as its derivative is also a vector representing angular velocity**:
\begin{equation}
\tcmbox{\bm{\mathcal{X}} = \begin{bmatrix}\bm{x}\_p \\ \bm{\theta}\end{bmatrix}; \quad
\boxed{\bm{\mathcal{X}} = \begin{bmatrix}\bm{x}\_p \\ \bm{\theta}\end{bmatrix}; \quad
\dot{\bm{\mathcal{X}}} = \begin{bmatrix}\bm{v}\_p \\ \bm{\omega}\end{bmatrix}; \quad
\ddot{\bm{\mathcal{X}}} = \begin{bmatrix}\bm{a}\_p \\ \dot{\bm{\omega}}\end{bmatrix}}
\end{equation}
@ -1736,7 +1736,7 @@ in which
As shown in Figure [fig:stewart_forward_dynamics](#fig:stewart_forward_dynamics), it is **assumed that actuator forces and external disturbance wrench applied to the manipulator are given and the resulting trajectory of the moving platform is to be determined**.
<a id="org10dda89"></a>
<a id="orgbeb7253"></a>
{{< figure src="/ox-hugo/taghirad13_stewart_forward_dynamics.png" caption="Figure 13: Flowchart of forward dynamics implementation sequence" >}}
@ -1769,7 +1769,7 @@ Therefore, actuator forces \\(\bm{\tau}\\) are computed in the simulation from
\bm{\tau} = \bm{J}^{-T} \left( \bm{M}(\bm{\mathcal{X}})\ddot{\bm{\mathcal{X}}} + \bm{C}(\bm{\mathcal{X}}, \dot{\bm{\mathcal{X}}})\dot{\bm{\mathcal{X}}} + \bm{G}(\bm{\mathcal{X}}) - \bm{\mathcal{F}}\_d \right)
\end{equation}
<a id="org483a1e4"></a>
<a id="orgeaa02c4"></a>
{{< figure src="/ox-hugo/taghirad13_stewart_inverse_dynamics.png" caption="Figure 14: Flowchart of inverse dynamics implementation sequence" >}}
@ -1794,7 +1794,7 @@ Therefore, actuator forces \\(\bm{\tau}\\) are computed in the simulation from
## Motion Control {#motion-control}
<a id="orgfe178f0"></a>
<a id="org1ca8f23"></a>
### Introduction {#introduction}
@ -1815,7 +1815,7 @@ However, using advanced techniques in nonlinear and MIMO control permits to over
### Controller Topology {#controller-topology}
<a id="orgc4c567e"></a>
<a id="orgfaf4318"></a>
<div class="cbox">
<div></div>
@ -1829,7 +1829,7 @@ Let us use the motion variables as the generalized coordinate of the moving plat
Consider the general closed-form dynamics formulation of a parallel robot
\begin{equation}
\tcmbox{\bm{M}(\bm{\mathcal{X}})\ddot{\bm{\mathcal{X}}} + \bm{C}(\bm{\mathcal{X}}, \dot{\bm{\mathcal{X}}})\dot{\bm{\mathcal{X}}} + \bm{G}(\bm{\mathcal{X}}) = \bm{\mathcal{F}}}
\boxed{\bm{M}(\bm{\mathcal{X}})\ddot{\bm{\mathcal{X}}} + \bm{C}(\bm{\mathcal{X}}, \dot{\bm{\mathcal{X}}})\dot{\bm{\mathcal{X}}} + \bm{G}(\bm{\mathcal{X}}) = \bm{\mathcal{F}}}
\end{equation}
where
@ -1864,7 +1864,7 @@ Figure [fig:general_topology_motion_feedback](#fig:general_topology_motion_feedb
In such a structure, the measured position and orientation of the manipulator is compared to its desired value to generate the **motion error vector** \\(\bm{e}\_\mathcal{X}\\).
The controller uses this error information to generate suitable commands for the actuators to minimize the tracking error.<br />
<a id="orge8ba1bf"></a>
<a id="org909a7b6"></a>
{{< figure src="/ox-hugo/taghirad13_general_topology_motion_feedback.png" caption="Figure 15: The general topology of motion feedback control: motion variable \\(\bm{\mathcal{X}}\\) is measured" >}}
@ -1874,7 +1874,7 @@ The relation between the **differential motion variables** \\(\dot{\bm{q}}\\) an
It is then possible to use the forward kinematic analysis to calculate \\(\bm{\mathcal{X}}\\) from the measured joint variables \\(\bm{q}\\), and one may use the control topology depicted in Figure [fig:general_topology_motion_feedback_bis](#fig:general_topology_motion_feedback_bis) to implement such a controller.
<a id="org58f13d1"></a>
<a id="orged0d932"></a>
{{< figure src="/ox-hugo/taghirad13_general_topology_motion_feedback_bis.png" caption="Figure 16: The general topology of motion feedback control: the active joint variable \\(\bm{q}\\) is measured" >}}
@ -1888,7 +1888,7 @@ To overcome the implementation problem of the control topology in Figure [fig:ge
In this topology, depicted in Figure [fig:general_topology_motion_feedback_ter](#fig:general_topology_motion_feedback_ter), the desired motion trajectory of the robot \\(\bm{\mathcal{X}}\_d\\) is used in an **inverse kinematic analysis** to find the corresponding desired values for joint variable \\(\bm{q}\_d\\).
Hence, the controller is designed based on the **joint space error** \\(\bm{e}\_q\\).
<a id="org48e4f9a"></a>
<a id="org2a995a3"></a>
{{< figure src="/ox-hugo/taghirad13_general_topology_motion_feedback_ter.png" caption="Figure 17: The general topology of motion feedback control: the active joint variable \\(\bm{q}\\) is measured, and the inverse kinematic analysis is used" >}}
@ -1902,7 +1902,7 @@ For the topology in Figure [fig:general_topology_motion_feedback_ter](#fig:gener
To generate a **direct input to output relation in the task space**, consider the topology depicted in Figure [fig:general_topology_motion_feedback_quater](#fig:general_topology_motion_feedback_quater).
A force distribution block is added which maps the generated wrench in the task space \\(\bm{\mathcal{F}}\\), to its corresponding actuator forces/torque \\(\bm{\tau}\\).
<a id="orgaaaa6c0"></a>
<a id="orgfb3d861"></a>
{{< figure src="/ox-hugo/taghirad13_general_topology_motion_feedback_quater.png" caption="Figure 18: The general topology of motion feedback control in task space: the motion variable \\(\bm{\mathcal{X}}\\) is measured, and the controller output generates wrench in task space" >}}
@ -1912,7 +1912,7 @@ For a fully parallel manipulator such as the Stewart-Gough platform, this mappin
### Motion Control in Task Space {#motion-control-in-task-space}
<a id="orgdc25eb0"></a>
<a id="org16aa3bf"></a>
#### Decentralized PD Control {#decentralized-pd-control}
@ -1921,7 +1921,7 @@ In the control structure in Figure [fig:decentralized_pd_control_task_space](#fi
The decentralized controller consists of **six disjoint linear controllers** acting on each error component \\(\bm{e}\_x = [e\_x,\ e\_y,\ e\_z,\ e\_{\theta\_x},\ e\_{\theta\_y},\ e\_{\theta\_z}]\\).
The PD controller is denoted by \\(\bm{K}\_d s + \bm{K}\_p\\), in which \\(\bm{K}\_d\\) and \\(\bm{K}\_p\\) are \\(6 \times 6\\) **diagonal matrices** denoting the derivative and proportional controller gains for each error term.
<a id="org606bd43"></a>
<a id="org0b974ce"></a>
{{< figure src="/ox-hugo/taghirad13_decentralized_pd_control_task_space.png" caption="Figure 19: Decentralized PD controller implemented in task space" >}}
@ -1944,7 +1944,7 @@ A feedforward wrench denoted by \\(\bm{\mathcal{F}}\_{ff}\\) may be added to the
This term is generated from the dynamic model of the manipulator in the task space, represented in a closed form by the following equation:
\\[ \bm{\mathcal{F}}\_{ff} = \bm{\hat{M}}(\bm{\mathcal{X}}\_d)\ddot{\bm{\mathcal{X}}}\_d + \bm{\hat{C}}(\bm{\mathcal{X}}\_d, \dot{\bm{\mathcal{X}}}\_d)\dot{\bm{\mathcal{X}}}\_d + \bm{\hat{G}}(\bm{\mathcal{X}}\_d) \\]
<a id="orgc82e82c"></a>
<a id="orgecae3b2"></a>
{{< figure src="/ox-hugo/taghirad13_feedforward_control_task_space.png" caption="Figure 20: Feed forward wrench added to the decentralized PD controller in task space" >}}
@ -2007,7 +2007,7 @@ Furthermore, mass matrix is added in the forward path in addition to the desired
As for the feedforward control, the **dynamics and kinematic parameters of the robot are needed**, and in practice estimates of these matrices are used.<br />
<a id="org91fbf3f"></a>
<a id="orgb029958"></a>
{{< figure src="/ox-hugo/taghirad13_inverse_dynamics_control_task_space.png" caption="Figure 21: General configuration of inverse dynamics control implemented in task space" >}}
@ -2129,14 +2129,14 @@ in which
\\[ \bm{\eta} = \bm{M}^{-1} \left( \tilde{\bm{M}} \bm{a}\_r + \tilde{\bm{C}} \dot{\bm{\mathcal{X}}} + \tilde{\bm{G}} \right) \\]
is a measure of modeling uncertainty.
<a id="orgde515fb"></a>
<a id="orgb942112"></a>
{{< figure src="/ox-hugo/taghirad13_robust_inverse_dynamics_task_space.png" caption="Figure 22: General configuration of robust inverse dynamics control implemented in the task space" >}}
#### Adaptive Inverse Dynamics Control {#adaptive-inverse-dynamics-control}
<a id="org12cdae3"></a>
<a id="orgbe7cc8a"></a>
{{< figure src="/ox-hugo/taghirad13_adaptative_inverse_control_task_space.png" caption="Figure 23: General configuration of adaptative inverse dynamics control implemented in task space" >}}
@ -2162,13 +2162,13 @@ The relation between the task space variables to their counterparts in the joint
Although both analyses involve solution to a set of non-linear equations, for parallel manipulators, inverse kinematic solution proves to be much easier to obtain than that of forward kinematic solution.<br />
This relation in **differential kinematics** is much simpler and can be completely determined by the Jacobian matrix:
\\[ \tcmbox{\dot{\bm{q}} = \bm{J} \dot{\bm{\mathcal{X}}} \Longrightarrow \dot{\bm{\mathcal{X}}} = \bm{J}^{-1} \dot{\bm{q}}} \\]
\\[ \boxed{\dot{\bm{q}} = \bm{J} \dot{\bm{\mathcal{X}}} \Longrightarrow \dot{\bm{\mathcal{X}}} = \bm{J}^{-1} \dot{\bm{q}}} \\]
The acceleration variables are then:
\\[ \ddot{\bm{q}} = \dot{\bm{J}} \dot{\bm{\mathcal{X}}} + \bm{J} \ddot{\mathcal{X}} \Longrightarrow \ddot{X} = \bm{J}^{-1} \ddot{\bm{q}} - \bm{J}^{-1} \dot{\bm{J}} \dot{\bm{\mathcal{X}}} \\]
Furthermore, the relation between the actuator force vector \\(\bm{\tau}\\) to the corresponding task space wrench is given by:
\\[ \tcmbox{\bm{\mathcal{F}} = \bm{J}^T \bm{\tau} \Longrightarrow \bm{\tau} = \bm{J}^{-T} \bm{\mathcal{F}}} \\]
\\[ \boxed{\bm{\mathcal{F}} = \bm{J}^T \bm{\tau} \Longrightarrow \bm{\tau} = \bm{J}^{-T} \bm{\mathcal{F}}} \\]
Substituting \\(\dot{\bm{\mathcal{X}}}\\) and \\(\ddot{\bm{\mathcal{X}}}\\) from the above equations into the dynamic formulation of the parallel robot gives:
@ -2221,7 +2221,7 @@ In this control structure, depicted in Figure [fig:decentralized_pd_control_join
The PD controller is denoted by \\(\bm{K}\_d s + \bm{K}\_p\\), where \\(\bm{K}\_d\\) and \\(\bm{K}\_p\\) are \\(n \times n\\) **diagonal** matrices denoting the derivative and proportional controller gains, respectively.<br />
<a id="orgb5d74d6"></a>
<a id="org5841aae"></a>
{{< figure src="/ox-hugo/taghirad13_decentralized_pd_control_joint_space.png" caption="Figure 24: Decentralized PD controller implemented in joint space" >}}
@ -2243,7 +2243,7 @@ To remedy these shortcomings, some modifications have been proposed to this stru
The tracking performance of the simple PD controller implemented in the joint space is usually not sufficient at different configurations.
To improve the tracking performance, a feedforward actuator force denoted by \\(\bm{\tau}\_{ff}\\) may be added to the structure of the controller as depicted in Figure [fig:feedforward_pd_control_joint_space](#fig:feedforward_pd_control_joint_space).
<a id="orgf7c6a31"></a>
<a id="org934eb1c"></a>
{{< figure src="/ox-hugo/taghirad13_feedforward_pd_control_joint_space.png" caption="Figure 25: Feed forward actuator force added to the decentralized PD controller in joint space" >}}
@ -2291,7 +2291,7 @@ Furthermore, the mass matrix is acting in the **forward path**, in addition to t
Note that to generate this term, the **dynamic formulation** of the robot, and its **kinematic and dynamic parameters are needed**.
In practice, exact knowledge of dynamic matrices are not available, and there estimates are used.<br />
<a id="org94f6836"></a>
<a id="org7f6d251"></a>
{{< figure src="/ox-hugo/taghirad13_inverse_dynamics_control_joint_space.png" caption="Figure 26: General configuration of inverse dynamics control implemented in joint space" >}}
@ -2567,7 +2567,7 @@ Hence, it is recommended to design and implement controllers in the task space,
## Force Control {#force-control}
<a id="org3d18b1c"></a>
<a id="org5f2ddee"></a>
### Introduction {#introduction}
@ -2623,7 +2623,7 @@ The output control loop is called the **primary loop**, while the inner loop is
</div>
<a id="orga3a5181"></a>
<a id="orgf81b89d"></a>
{{< figure src="/ox-hugo/taghirad13_cascade_control.png" caption="Figure 27: Block diagram of a closed-loop system with cascade control" >}}
@ -2657,7 +2657,7 @@ As seen in Figure [fig:taghira13_cascade_force_outer_loop](#fig:taghira13_cascad
The output of motion controller is also designed in the task space, and to convert it to implementable actuator force \\(\bm{\tau}\\), the force distribution block is considered in this topology.<br />
<a id="orgf32a158"></a>
<a id="orgf39e436"></a>
{{< figure src="/ox-hugo/taghira13_cascade_force_outer_loop.png" caption="Figure 28: Cascade topology of force feedback control: position in inner loop and force in outer loop. Moving platform wrench \\(\bm{\mathcal{F}}\\) and motion variable \\(\bm{\mathcal{X}}\\) are measured in the task space" >}}
@ -2665,7 +2665,7 @@ Other alternatives for force control topology may be suggested based on the vari
If the force is measured in the joint space, the topology suggested in Figure [fig:taghira13_cascade_force_outer_loop_tau](#fig:taghira13_cascade_force_outer_loop_tau) can be used.
In this topology, the measured actuator force vector \\(\bm{\tau}\\) is mapped into its corresponding wrench in the task space by the Jacobian transpose mapping \\(\bm{\mathcal{F}} = \bm{J}^T \bm{\tau}\\).<br />
<a id="org8584b77"></a>
<a id="orgbdf64cb"></a>
{{< figure src="/ox-hugo/taghira13_cascade_force_outer_loop_tau.png" caption="Figure 29: Cascade topology of force feedback control: position in inner loop and force in outer loop. Actuator forces \\(\bm{\tau}\\) and motion variable \\(\bm{\mathcal{X}}\\) are measured" >}}
@ -2676,7 +2676,7 @@ However, as the inner loop is constructed in the joint space, the desired motion
Therefore, the structure and characteristics of the position controller in this topology is totally different from that given in the first two topologies.<br />
<a id="org9f5853b"></a>
<a id="org5701992"></a>
{{< figure src="/ox-hugo/taghira13_cascade_force_outer_loop_tau_q.png" caption="Figure 30: Cascade topology of force feedback control: position in inner loop and force in outer loop. Actuator forces \\(\bm{\tau}\\) and joint motion variable \\(\bm{q}\\) are measured in the joint space" >}}
@ -2694,7 +2694,7 @@ By this means, when the manipulator is not in contact with a stiff environment,
However, when there is interacting wrench \\(\bm{\mathcal{F}}\_e\\) applied to the moving platform, this structure controls the force-motion relation.
This configuration may be seen as if the **outer loop generates a desired force trajectory for the inner loop**.<br />
<a id="orgc28d73d"></a>
<a id="orge5122a4"></a>
{{< figure src="/ox-hugo/taghira13_cascade_force_inner_loop_F.png" caption="Figure 31: Cascade topology of force feedback control: force in inner loop and position in outer loop. Moving platform wrench \\(\bm{\mathcal{F}}\\) and motion variable \\(\bm{\mathcal{X}}\\) are measured in the task space" >}}
@ -2702,7 +2702,7 @@ Other alternatives for control topology may be suggested based on the variations
If the force is measured in the joint space, control topology shown in Figure [fig:taghira13_cascade_force_inner_loop_tau](#fig:taghira13_cascade_force_inner_loop_tau) can be used.
In such case, the Jacobian transpose is used to map the actuator force to its corresponding wrench in the task space.<br />
<a id="org1b0b0fb"></a>
<a id="org47655dc"></a>
{{< figure src="/ox-hugo/taghira13_cascade_force_inner_loop_tau.png" caption="Figure 32: Cascade topology of force feedback control: force in inner loop and position in outer loop. Actuator forces \\(\bm{\tau}\\) and motion variable \\(\bm{\mathcal{X}}\\) are measured" >}}
@ -2711,7 +2711,7 @@ The inner loop is based on the measured actuator force vector in the joint space
In this topology, the desired motion in the task space is mapped into the joint space using **inverse kinematic** solution, and **both the position and force feedback controllers are designed in the joint space**.
Thus, independent controllers for each joint may be suitable for this topology.
<a id="orgf6e06eb"></a>
<a id="org4c94934"></a>
{{< figure src="/ox-hugo/taghira13_cascade_force_inner_loop_tau_q.png" caption="Figure 33: Cascade topology of force feedback control: force in inner loop and position in outer loop. Actuator forces \\(\bm{\tau}\\) and joint motion variable \\(\bm{q}\\) are measured in the joint space" >}}
@ -2730,7 +2730,7 @@ Thus, independent controllers for each joint may be suitable for this topology.
### Direct Force Control {#direct-force-control}
<a id="orgc96bfaa"></a>
<a id="org8390562"></a>
{{< figure src="/ox-hugo/taghira13_direct_force_control.png" caption="Figure 34: Direct force control scheme, force feedback in the outer loop and motion feedback in the inner loop" >}}
@ -2821,7 +2821,7 @@ The impedance of the system may be found from the Laplace transform of the above
</div>
<a id="org829b469"></a>
<a id="org9d33331"></a>
{{< figure src="/ox-hugo/taghirad13_impedance_control_rlc.png" caption="Figure 35: Analogy of electrical impedance in (a) an electrical RLC circuit to (b) a mechanical mass-spring-damper system" >}}
@ -2880,7 +2880,7 @@ Moreover, direct force-tracking objective is not assigned in this control scheme
However, an auxiliary force trajectory \\(\bm{\mathcal{F}}\_a\\) is generated from the motion control law and is used as the reference for the force tracking.
By this means, no prescribed force trajectory is tracked, while the **motion control scheme would advise a force trajectory for the robot to ensure the desired impedance regulation**.<br />
<a id="org365fe17"></a>
<a id="org1fdf95b"></a>
{{< figure src="/ox-hugo/taghira13_impedance_control.png" caption="Figure 36: Impedance control scheme; motion feedback in the outer loop and force feedback in the inner loop" >}}
@ -2918,4 +2918,4 @@ However, note that for a good performance, an accurate model of the system is re
## Bibliography {#bibliography}
<a id="orgf8aae74"></a>Taghirad, Hamid. 2013. _Parallel Robots : Mechanics and Control_. Boca Raton, FL: CRC Press.
<a id="org8f0ac84"></a>Taghirad, Hamid. 2013. _Parallel Robots : Mechanics and Control_. Boca Raton, FL: CRC Press.