From 89c144bee39bbc4c0e93b19a51afca6273ec1995 Mon Sep 17 00:00:00 2001 From: Thomas Dehaeze Date: Tue, 17 Dec 2024 16:26:06 +0100 Subject: [PATCH] Update Content - 2024-12-17 --- content/book/taghirad13_paral.md | 56 ++++++++++++++++---------------- 1 file changed, 28 insertions(+), 28 deletions(-) diff --git a/content/book/taghirad13_paral.md b/content/book/taghirad13_paral.md index a8aae79..e883bf8 100644 --- a/content/book/taghirad13_paral.md +++ b/content/book/taghirad13_paral.md @@ -264,7 +264,7 @@ If the pose of a rigid body \\(\\{{}^A\bm{R}\_B, {}^A\bm{P}\_{O\_B}\\}\\) is giv ### Homogeneous Transformations {#homogeneous-transformations} -To describe general transformations, we introduce the \\(4\times1\\) **homogeneous coordinates**, and Eq. is generalized to +To describe general transformations, we introduce the \\(4\times1\\) **homogeneous coordinates**, and Eq. \eqref{eq:chasles\_therorem} is generalized to \begin{equation} \label{eq:homogeneous\_transformation} \boxed{{}^A\bm{P} = {}^A\bm{T}\_B {}^B\bm{P}} @@ -620,7 +620,7 @@ The direction of \\(\bm{\Omega}\\) indicates the instantaneous axis of rotation -The angular velocity vector is related to the screw formalism by equation . +The angular velocity vector is related to the screw formalism by equation \eqref{eq:angular\_velocity\_vector}. \begin{equation} \label{eq:angular\_velocity\_vector} \boxed{\bm{\Omega} \triangleq \dot{\theta} \hat{\bm{s}}} @@ -695,7 +695,7 @@ The time derivative of the rotation matrix \\({}^A\dot{\bm{R}}\_B\\) is: \boxed{{}^A\dot{\bm{R}}\_B = {}^A\bm{\Omega}^\times \ {}^A\bm{R}\_B} \end{equation} -And we finally obtain equation . +And we finally obtain equation \eqref{eq:absolute\_velocity\_formula}.
@@ -755,7 +755,7 @@ The **general Jacobian matrix** is defined as: \dot{\bm{q}} = \bm{J} \dot{\bm{\mathcal{X}}} \end{equation} -From equation , we have: +From equation \eqref{eq:jacobians}, we have: \begin{equation} \bm{J} = {\bm{J}\_q}^{-1} \bm{J}\_x @@ -842,7 +842,7 @@ Moreover, we have: - \\({}^A\dot{\bm{R}}\_B {}^B\bm{b}\_i = {}^A\bm{\omega} \times {}^A\bm{R}\_B {}^B\bm{b}\_i = {}^A\bm{\omega} \times {}^A\bm{b}\_i\\) in which \\({}^A\bm{\omega}\\) denotes the angular velocity of the moving platform expressed in the fixed frame \\(\\{\bm{A}\\}\\). - \\(l\_i {}^A\dot{\hat{\bm{s}}}\_i = l\_i \left( {}^A\bm{\omega}\_i \times \hat{\bm{s}}\_i \right)\\) in which \\({}^A\bm{\omega}\_i\\) is the angular velocity of limb \\(i\\) express in fixed frame \\(\\{\bm{A}\\}\\). -Then, the velocity loop closure simplifies to +Then, the velocity loop closure \eqref{eq:loop\_closure\_limb\_diff} simplifies to \\[ {}^A\bm{v}\_p + {}^A\bm{\omega} \times {}^A\bm{b}\_i = \dot{l}\_i {}^A\hat{\bm{s}}\_i + l\_i ({}^A\bm{\omega}\_i \times \hat{\bm{s}}\_i) \\] By dot multiply both side of the equation by \\(\hat{\bm{s}}\_i\\): @@ -880,9 +880,9 @@ We then omit the superscript \\(A\\) and we can rearrange the 6 equations into a #### Singularity Analysis {#singularity-analysis} It is of primary importance to avoid singularities in a given workspace. -To study the singularity configurations of the Stewart-Gough platform, we consider the Jacobian matrix determined with the equation .
+To study the singularity configurations of the Stewart-Gough platform, we consider the Jacobian matrix determined with the equation \eqref{eq:jacobian\_formula\_stewart}.
-From equation , it is clear that for the Stewart-Gough platform, \\(\bm{J}\_q = \bm{I}\\) and \\(\bm{J}\_x = \bm{J}\\). +From equation \eqref{eq:jacobians}, it is clear that for the Stewart-Gough platform, \\(\bm{J}\_q = \bm{I}\\) and \\(\bm{J}\_x = \bm{J}\\). Hence the manipulator has **no inverse kinematic singularities** within the manipulator workspace, but **may possess forward kinematic singularity** when \\(\bm{J}\\) becomes rank deficient. This may occur when \\[ \det \bm{J} = 0 \\] @@ -1001,7 +1001,7 @@ The relation between the applied actuator force \\(\tau\_i\\) and the correspond in which \\(k\_i\\) denotes the **stiffness constant of the actuator**.
-Re-writing the equation for all limbs in a matrix form result in +Re-writing the equation \eqref{eq:stiffness\_actuator} for all limbs in a matrix form result in \begin{equation} \label{eq:stiffness\_matrix\_relation} \boxed{\bm{\tau} = \mathcal{K} \cdot \Delta \bm{q}} @@ -1010,7 +1010,7 @@ Re-writing the equation for all limbs in a matrix form r in which \\(\bm{\tau}\\) is the vector of actuator forces, and \\(\Delta \bm{q}\\) corresponds to the actuator deflections. \\(\mathcal{K} = \text{diag}\left[ k\_1 \ k\_2 \dots k\_m \right]\\) is an \\(m \times m\\) diagonal matrix composed of the actuator stiffness constants.
-Writing the Jacobian relation given in equation for infinitesimal deflection read +Writing the Jacobian relation given in equation \eqref{eq:jacobian\_disp} for infinitesimal deflection read \begin{equation} \label{eq:jacobian\_disp\_inf} \Delta \bm{q} = \bm{J} \cdot \Delta \bm{\mathcal{X}} @@ -1018,19 +1018,19 @@ Writing the Jacobian relation given in equation for infinites in which \\(\Delta \bm{\mathcal{X}} = [\Delta x\ \Delta y\ \Delta z\ \Delta\theta x\ \Delta\theta y\ \Delta\theta z]\\) is the infinitesimal linear and angular deflection of the moving platform. -Furthermore, rewriting the Jacobian as the projection of actuator forces to the moving platform gives +Furthermore, rewriting the Jacobian as the projection of actuator forces to the moving platform \eqref{eq:jacobian\_forces} gives \begin{equation} \label{eq:jacobian\_force\_inf} \bm{\mathcal{F}} = \bm{J}^T \bm{\tau} \end{equation} -Hence, by substituting and in , we obtain: +Hence, by substituting \eqref{eq:stiffness\_matrix\_relation} and \eqref{eq:jacobian\_disp\_inf} in \eqref{eq:jacobian\_force\_inf}, we obtain: \begin{equation} \label{eq:stiffness\_jacobian} \boxed{\bm{\mathcal{F}} = \underbrace{\bm{J}^T \mathcal{K} \bm{J}}\_{\bm{K}} \cdot \Delta \bm{\mathcal{X}}} \end{equation} -Equation implies that the moving platform output wrench is related to its deflection by the **stiffness matrix** \\(K\\). +Equation \eqref{eq:stiffness\_jacobian} implies that the moving platform output wrench is related to its deflection by the **stiffness matrix** \\(K\\).
@@ -1208,7 +1208,7 @@ where \\(\\{\theta, \hat{\bm{s}}\\}\\) are the screw parameters representing the
-As shown by , the angular acceleration of the rigid body is also along the screw axis \\(\hat{\bm{s}}\\) with a magnitude equal to \\(\ddot{\theta}\\). +As shown by \eqref{eq:angular\_acceleration}, the angular acceleration of the rigid body is also along the screw axis \\(\hat{\bm{s}}\\) with a magnitude equal to \\(\ddot{\theta}\\). ##### Linear Acceleration of a Point {#linear-acceleration-of-a-point} @@ -1305,7 +1305,7 @@ in which ##### Principal Axes {#principal-axes} -As seen in equation , the inertia matrix elements are a function of mass distribution of the rigid body with respect to the frame \\(\\{\bm{A}\\}\\). +As seen in equation \eqref{eq:moment\_inertia}, the inertia matrix elements are a function of mass distribution of the rigid body with respect to the frame \\(\\{\bm{A}\\}\\). Hence, it is possible to find **orientations of frame** \\(\\{\bm{A}\\}\\) in which the product of inertia terms vanish and inertia matrix becomes **diagonal**: \begin{equation} \label{eq:inertia\_matrix\_diagonal} @@ -1393,10 +1393,10 @@ Therefore, angular momentum of the rigid body about point \\(A\\) is reduced to in which \\[ {}^C\bm{H} = \int\_V \bm{r} \times (\bm{\Omega} \times \bm{r}) \rho dV = {}^C\bm{I} \cdot \bm{\Omega} \\] -Equation reveals that angular momentum of a rigid body about a point \\(A\\) can be written as \\(\bm{p}\_c \times \bm{G}\_c\\), which is the contribution of linear momentum of the rigid body about point \\(A\\), and \\({}^C\bm{H}\\) which is the angular momentum of the rigid body about the center of mass. +Equation \eqref{eq:angular\_momentum} reveals that angular momentum of a rigid body about a point \\(A\\) can be written as \\(\bm{p}\_c \times \bm{G}\_c\\), which is the contribution of linear momentum of the rigid body about point \\(A\\), and \\({}^C\bm{H}\\) which is the angular momentum of the rigid body about the center of mass. This also highlights the important of the center of mass in the dynamic analysis of rigid bodies. -If the center of mass is taken as the reference point, the relation describing angular momentum is very analogous to that of linear momentum . +If the center of mass is taken as the reference point, the relation describing angular momentum \eqref{eq:angular\_momentum} is very analogous to that of linear momentum \eqref{eq:linear\_momentum}. ##### Kinetic Energy {#kinetic-energy} @@ -1608,7 +1608,7 @@ in which \\(\bm{\mathcal{X}} = [\bm{x}\_P, \bm{\theta}]^T\\) is the motion varia #### Closed-Form Dynamics {#closed-form-dynamics} -While dynamic formulation in the form of Equation can be used to simulate inverse dynamics of the Stewart-Gough platform, its implicit nature makes it unpleasant for the dynamic analysis and control. +While dynamic formulation in the form of Equation \eqref{eq:dynamic\_formulation\_implicit} can be used to simulate inverse dynamics of the Stewart-Gough platform, its implicit nature makes it unpleasant for the dynamic analysis and control. ##### Closed-Form Dynamics of the Limbs {#closed-form-dynamics-of-the-limbs} @@ -1666,7 +1666,7 @@ It is preferable to use the **screw coordinates** for representing the angular m \ddot{\bm{\mathcal{X}}} = \begin{bmatrix}\bm{a}\_p \\\ \dot{\bm{\omega}}\end{bmatrix}} \end{equation} -Equations and can be simply converted into a closed form of Equation with the following terms: +Equations \eqref{eq:dyn\_form\_implicit\_trans} and \eqref{eq:dyn\_form\_implicit\_rot} can be simply converted into a closed form of Equation \eqref{eq:close\_form\_dynamics\_platform} with the following terms: \begin{equation} \label{eq:close\_form\_dynamics\_stewart\_terms} \begin{aligned} @@ -1729,7 +1729,7 @@ As shown in [Figure 13](#figure--fig:stewart-forward-dynamics), it is **assumed {{< figure src="/ox-hugo/taghirad13_stewart_forward_dynamics.png" caption="Figure 13: Flowchart of forward dynamics implementation sequence" >}} -The closed-form dynamic formulation of the Stewart-Gough platform corresponds to the set of equations given in , whose terms are given in . +The closed-form dynamic formulation of the Stewart-Gough platform corresponds to the set of equations given in \eqref{eq:closed\_form\_dynamic\_stewart\_wanted}, whose terms are given in \eqref{eq:close\_form\_dynamics\_stewart\_terms}. ##### Inverse Dynamics Simulation {#inverse-dynamics-simulation} @@ -1744,11 +1744,11 @@ For such a trajectory, \\(\bm{\mathcal{X}}\_{d}(t)\\) and the time derivatives \ The next step is to solve the inverse kinematics of the manipulator and to find the limbs' linear and angular positions, velocity and acceleration as a function of the manipulator trajectory. The manipulator Jacobian matrix \\(\bm{J}\\) is also calculated in this step. -Next, the dynamic matrices given in the closed-form formulations of the limbs and the moving platform are calculated using equations and , respectively.
+Next, the dynamic matrices given in the closed-form formulations of the limbs and the moving platform are calculated using equations \eqref{eq:closed\_form\_intermediate\_parameters} and \eqref{eq:close\_form\_dynamics\_stewart\_terms}, respectively.
-To combine the corresponding matrices, an to generate the whole manipulator dynamics, it is necessary to find intermediate Jacobian matrices \\(\bm{J}\_i\\), given in , and then compute compatible matrices for the limbs given in . +To combine the corresponding matrices, an to generate the whole manipulator dynamics, it is necessary to find intermediate Jacobian matrices \\(\bm{J}\_i\\), given in \eqref{eq:jacobian\_intermediate}, and then compute compatible matrices for the limbs given in \eqref{eq:closed\_form\_stewart\_manipulator}. Now that all the terms required to **computed to actuator forces required to generate such a trajectory** is computed, let us define \\(\bm{\mathcal{F}}\\) as the resulting Cartesian wrench applied to the moving platform. -This wrench can be calculated from the summation of all inertial and external forces **excluding the actuator torques** \\(\bm{\tau}\\) in the closed-form dynamic formulation . +This wrench can be calculated from the summation of all inertial and external forces **excluding the actuator torques** \\(\bm{\tau}\\) in the closed-form dynamic formulation \eqref{eq:closed\_form\_dynamic\_stewart\_wanted}. By this definition, \\(\bm{\mathcal{F}}\\) can be viewed as the projector of the actuator forces acting on the manipulator, mapped to the Cartesian space. Since there is no redundancy in actuation in the Stewart-Gough manipulator, the Jacobian matrix \\(\bm{J}\\), squared and actuator forces can be uniquely determined from this wrench, by \\(\bm{\tau} = \bm{J}^{-T} \bm{\mathcal{F}}\\), provided \\(\bm{J}\\) is non-singular. @@ -2043,9 +2043,9 @@ These are the reasons why, in practice, IDC control is extended to different for To develop the simplest possible implementable IDC, let us recall dynamic formulation complexities: -- the manipulator mass matrix \\(\bm{M}(\bm{\mathcal{X}})\\) is derived from kinetic energy of the manipulator (Eq. ) -- the gravity vector \\(\bm{G}(\bm{\mathcal{X}})\\) is derived from potential energy (Eq. ) -- the Coriolis and centrifugal matrix \\(\bm{C}(\bm{\mathcal{X}}, \dot{\bm{\mathcal{X}}})\\) is derived from Eq. +- the manipulator mass matrix \\(\bm{M}(\bm{\mathcal{X}})\\) is derived from kinetic energy of the manipulator (Eq. \eqref{eq:kinetic\_energy}) +- the gravity vector \\(\bm{G}(\bm{\mathcal{X}})\\) is derived from potential energy (Eq. \eqref{eq:gravity\_vectory}) +- the Coriolis and centrifugal matrix \\(\bm{C}(\bm{\mathcal{X}}, \dot{\bm{\mathcal{X}}})\\) is derived from Eq. \eqref{eq:gravity\_vectory} The computation of the Coriolis and centrifugal matrix is more intensive than that of the mass matrix. Gravity vector is more easily computable. @@ -2053,7 +2053,7 @@ Gravity vector is more easily computable. However, it is shown that certain properties hold for mass matrix, gravity vector and Coriolis and centrifugal matrix, which might be directly used in the control techniques developed for parallel manipulators. One of the most important properties of dynamic matrices is the skew-symmetric property of the matrix \\(\dot{\bm{M}} - 2 \bm{C}\\) .
-Consider dynamic formulation of parallel robot given in Eq. , in which the skew-symmetric property of dynamic matrices is satisfied. +Consider dynamic formulation of parallel robot given in Eq. \eqref{eq:closed\_form\_dynamic\_formulation}, in which the skew-symmetric property of dynamic matrices is satisfied. The simplest form of IDC control effort \\(\bm{\mathcal{F}}\\) consists of: \\[ \bm{\mathcal{F}} = \bm{\mathcal{F}}\_{pd} + \bm{\mathcal{F}}\_{fl} \\] in which the first term \\(\bm{\mathcal{F}}\_{pd}\\) is generated by the simplified PD form on the motion error: @@ -2091,7 +2091,7 @@ A global understanding of the trade-offs involved in each method is needed to em Various sources of uncertainties such as unmodelled dynamics, unknown parameters, calibration error, unknown disturbance wrenches, and varying payloads may exist, and are not seen in dynamic model of the manipulator. -To consider these modeling uncertainty in the closed-loop performance of the manipulator, recall the general closed-form dynamic formulation of the manipulator given in Eq. , and modify the inverse dynamics control input \\(\bm{\mathcal{F}}\\) as +To consider these modeling uncertainty in the closed-loop performance of the manipulator, recall the general closed-form dynamic formulation of the manipulator given in Eq. \eqref{eq:closed\_form\_dynamic\_formulation}, and modify the inverse dynamics control input \\(\bm{\mathcal{F}}\\) as \begin{align\*} \bm{\mathcal{F}} &= \hat{\bm{M}}(\bm{\mathcal{X}}) \bm{a}\_r + \hat{\bm{C}}(\bm{\mathcal{X}}, \dot{\bm{\mathcal{X}}}) \dot{\bm{\mathcal{X}}} + \hat{\bm{G}}(\bm{\mathcal{X}})\\\\ @@ -2183,7 +2183,7 @@ with:
-Equation represents the closed form dynamic formulation of a general parallel robot in the joint space.
+Equation \eqref{eq:dynamics\_joint\_space} represents the closed form dynamic formulation of a general parallel robot in the joint space.
Note that the dynamic matrices are **not** explicitly represented in terms of the joint variable vector \\(\bm{q}\\). In fact, to fully derive these matrices, the Jacobian matrices must be computed and are generally derived as a function of the motion variables \\(\bm{\mathcal{X}}\\).