Update Content - 2021-02-01
This commit is contained in:
parent
06d3db5f0b
commit
cab5a4a66f
@ -8,7 +8,7 @@ Tags
|
||||
: [Stewart Platforms]({{< relref "stewart_platforms" >}}), [Reference Books]({{< relref "reference_books" >}})
|
||||
|
||||
Reference
|
||||
: ([Taghirad 2013](#org83723e5))
|
||||
: ([Taghirad 2013](#orge267b8c))
|
||||
|
||||
Author(s)
|
||||
: Taghirad, H.
|
||||
@ -19,7 +19,7 @@ Year
|
||||
|
||||
## Introduction {#introduction}
|
||||
|
||||
<a id="org26c842b"></a>
|
||||
<a id="org157e93f"></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.
|
||||
@ -44,7 +44,7 @@ The control of parallel robots is elaborated in the last two chapters, in which
|
||||
|
||||
## Motion Representation {#motion-representation}
|
||||
|
||||
<a id="orgf4397da"></a>
|
||||
<a id="org363db2c"></a>
|
||||
|
||||
|
||||
### Spatial Motion Representation {#spatial-motion-representation}
|
||||
@ -59,7 +59,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="orgc60e548"></a>
|
||||
<a id="org5533e51"></a>
|
||||
|
||||
{{< figure src="/ox-hugo/taghirad13_rigid_body_motion.png" caption="Figure 1: Representation of a rigid body spatial motion" >}}
|
||||
|
||||
@ -84,7 +84,7 @@ 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](#org5798f66)).
|
||||
Its orientation has changed from a state represented by frame \\(\\{\bm{A}\\}\\) to its current orientation represented by frame \\(\\{\bm{B}\\}\\) (Figure [2](#org6f4a801)).
|
||||
|
||||
A \\(3 \times 3\\) rotation matrix \\({}^A\bm{R}\_B\\) is defined by
|
||||
|
||||
@ -106,7 +106,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="org5798f66"></a>
|
||||
<a id="org6f4a801"></a>
|
||||
|
||||
{{< figure src="/ox-hugo/taghirad13_rotation_matrix.png" caption="Figure 2: Pure rotation of a rigid body" >}}
|
||||
|
||||
@ -132,7 +132,7 @@ 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="org9900414"></a>
|
||||
<a id="orgee29ec0"></a>
|
||||
|
||||
{{< figure src="/ox-hugo/taghirad13_screw_axis_representation.png" caption="Figure 3: Pure rotation about a screw axis" >}}
|
||||
|
||||
@ -158,7 +158,7 @@ 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="orgac7b654"></a>
|
||||
<a id="orgb162cd6"></a>
|
||||
|
||||
{{< figure src="/ox-hugo/taghirad13_pitch-roll-yaw.png" caption="Figure 4: Definition of pitch, roll and yaw angles on an air plain" >}}
|
||||
|
||||
@ -363,7 +363,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="orga843e45"></a>
|
||||
<a id="orgc1a7048"></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}\\}\\)" >}}
|
||||
|
||||
@ -426,7 +426,7 @@ Hence, the **inverse of the transformation matrix** can be obtain by
|
||||
|
||||
## Kinematics {#kinematics}
|
||||
|
||||
<a id="org08e19b3"></a>
|
||||
<a id="orgdc3f0a7"></a>
|
||||
|
||||
|
||||
### Introduction {#introduction}
|
||||
@ -533,7 +533,7 @@ The position of the point \\(O\_B\\) of the moving platform is described by the
|
||||
\end{bmatrix}
|
||||
\end{equation}
|
||||
|
||||
<a id="org42f2f1d"></a>
|
||||
<a id="org02bb8ee"></a>
|
||||
|
||||
{{< figure src="/ox-hugo/taghirad13_stewart_schematic.png" caption="Figure 6: Geometry of a Stewart-Gough platform" >}}
|
||||
|
||||
@ -586,7 +586,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="org626f75f"></a>
|
||||
<a id="org7462b3d"></a>
|
||||
|
||||
|
||||
### Introduction {#introduction}
|
||||
@ -683,7 +683,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="org977e004"></a>
|
||||
<a id="org38d1c64"></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}\\}\\)" >}}
|
||||
|
||||
@ -827,7 +827,7 @@ The corresponding configuration will be one in which an infinitesimal motion of
|
||||
|
||||
#### Velocity Loop Closure {#velocity-loop-closure}
|
||||
|
||||
The input joint rate is denoted by \\(\dot{\bm{\mathcal{L}}} = [ \dot{l}\_1, \dot{l}\_2, \dot{l}\_3, \dot{l}\_4, \dot{l}\_5, \dot{l}\_6 ]^T\\), and the output twist vector is denoted by \\(\dot{\bm{\mathcal{X}}} = [^A\bm{v}\_p, {}^A\bm{\omega}]^T\\).<br />
|
||||
The input joint rate is denoted by \\(\dot{\bm{\mathcal{L}}} = [ \dot{l}\_1, \dot{l}\_2, \dot{l}\_3, \dot{l}\_4, \dot{l}\_5, \dot{l}\_6 ]^T\\), and the output twist vector is denoted by \\(\dot{\bm{\mathcal{X}}} = [{}^A\bm{v}\_p, {}^A\bm{\omega}]^T\\).<br />
|
||||
|
||||
The jacobian matrix can be derived by formulating a velocity loop closure equation of each limb.
|
||||
The loop closure equations for each limb are:
|
||||
@ -942,7 +942,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="orgdceb41b"></a>
|
||||
<a id="org1e5d0ac"></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" >}}
|
||||
|
||||
@ -1099,7 +1099,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="org1ef7488"></a>
|
||||
<a id="org5661020"></a>
|
||||
|
||||
{{< figure src="/ox-hugo/taghirad13_stewart36.png" caption="Figure 9: Schematic of a 3-6 Stewart-Gough platform" >}}
|
||||
|
||||
@ -1129,7 +1129,7 @@ The largest axis of the stiffness transformation hyper-ellipsoid is given by thi
|
||||
|
||||
## Dynamics {#dynamics}
|
||||
|
||||
<a id="org1ba4719"></a>
|
||||
<a id="org7575df8"></a>
|
||||
|
||||
|
||||
### Introduction {#introduction}
|
||||
@ -1260,7 +1260,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="org50ad3d7"></a>
|
||||
<a id="org1e725b6"></a>
|
||||
|
||||
{{< figure src="/ox-hugo/taghirad13_mass_property_rigid_body.png" caption="Figure 10: Mass properties of a rigid body" >}}
|
||||
|
||||
@ -1374,7 +1374,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="org3298b54"></a>
|
||||
<a id="org5ee285a"></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\\)" >}}
|
||||
|
||||
@ -1519,7 +1519,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="org640d88d"></a>
|
||||
<a id="org503dfcf"></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" >}}
|
||||
|
||||
@ -1733,7 +1733,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="org7b02420"></a>
|
||||
<a id="org3d13427"></a>
|
||||
|
||||
{{< figure src="/ox-hugo/taghirad13_stewart_forward_dynamics.png" caption="Figure 13: Flowchart of forward dynamics implementation sequence" >}}
|
||||
|
||||
@ -1766,7 +1766,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="org46b6aea"></a>
|
||||
<a id="org7d05c5f"></a>
|
||||
|
||||
{{< figure src="/ox-hugo/taghirad13_stewart_inverse_dynamics.png" caption="Figure 14: Flowchart of inverse dynamics implementation sequence" >}}
|
||||
|
||||
@ -1791,7 +1791,7 @@ Therefore, actuator forces \\(\bm{\tau}\\) are computed in the simulation from
|
||||
|
||||
## Motion Control {#motion-control}
|
||||
|
||||
<a id="org5a83018"></a>
|
||||
<a id="org9d0691b"></a>
|
||||
|
||||
|
||||
### Introduction {#introduction}
|
||||
@ -1812,7 +1812,7 @@ However, using advanced techniques in nonlinear and MIMO control permits to over
|
||||
|
||||
### Controller Topology {#controller-topology}
|
||||
|
||||
<a id="org1581176"></a>
|
||||
<a id="orgd508d64"></a>
|
||||
|
||||
<div class="cbox">
|
||||
<div></div>
|
||||
@ -1861,7 +1861,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="orgfd5bffc"></a>
|
||||
<a id="org46eaf39"></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" >}}
|
||||
|
||||
@ -1871,7 +1871,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="org9c088d8"></a>
|
||||
<a id="org1c41f76"></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" >}}
|
||||
|
||||
@ -1885,7 +1885,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="org595eb7e"></a>
|
||||
<a id="org3605dfc"></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" >}}
|
||||
|
||||
@ -1899,7 +1899,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="org71c8d96"></a>
|
||||
<a id="org1ee8224"></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" >}}
|
||||
|
||||
@ -1909,7 +1909,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="org7a0eeda"></a>
|
||||
<a id="orgfa59a60"></a>
|
||||
|
||||
|
||||
#### Decentralized PD Control {#decentralized-pd-control}
|
||||
@ -1918,7 +1918,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="org2cb023e"></a>
|
||||
<a id="org1010d4c"></a>
|
||||
|
||||
{{< figure src="/ox-hugo/taghirad13_decentralized_pd_control_task_space.png" caption="Figure 19: Decentralized PD controller implemented in task space" >}}
|
||||
|
||||
@ -1941,7 +1941,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="org5be86ad"></a>
|
||||
<a id="org93f8916"></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" >}}
|
||||
|
||||
@ -2004,7 +2004,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="org40b744b"></a>
|
||||
<a id="org0b8b7da"></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" >}}
|
||||
|
||||
@ -2126,14 +2126,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="org8c0b9f0"></a>
|
||||
<a id="org6507df1"></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="org0913050"></a>
|
||||
<a id="orga4ee1ee"></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" >}}
|
||||
|
||||
@ -2218,7 +2218,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="orgb23393c"></a>
|
||||
<a id="org33c84d2"></a>
|
||||
|
||||
{{< figure src="/ox-hugo/taghirad13_decentralized_pd_control_joint_space.png" caption="Figure 24: Decentralized PD controller implemented in joint space" >}}
|
||||
|
||||
@ -2240,7 +2240,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="org1271f23"></a>
|
||||
<a id="org8250688"></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" >}}
|
||||
|
||||
@ -2288,7 +2288,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="org67c4d2d"></a>
|
||||
<a id="org3e13d23"></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" >}}
|
||||
|
||||
@ -2564,7 +2564,7 @@ Hence, it is recommended to design and implement controllers in the task space,
|
||||
|
||||
## Force Control {#force-control}
|
||||
|
||||
<a id="org5f01b29"></a>
|
||||
<a id="org0954a98"></a>
|
||||
|
||||
|
||||
### Introduction {#introduction}
|
||||
@ -2620,7 +2620,7 @@ The output control loop is called the **primary loop**, while the inner loop is
|
||||
|
||||
</div>
|
||||
|
||||
<a id="org8f72178"></a>
|
||||
<a id="orgfa4a25b"></a>
|
||||
|
||||
{{< figure src="/ox-hugo/taghirad13_cascade_control.png" caption="Figure 27: Block diagram of a closed-loop system with cascade control" >}}
|
||||
|
||||
@ -2654,7 +2654,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="org56b8cbe"></a>
|
||||
<a id="orgcb034a8"></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" >}}
|
||||
|
||||
@ -2662,7 +2662,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="org4f5db67"></a>
|
||||
<a id="org7a885fa"></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" >}}
|
||||
|
||||
@ -2673,7 +2673,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="org01704d8"></a>
|
||||
<a id="orgddea488"></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" >}}
|
||||
|
||||
@ -2691,7 +2691,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="orgc849b45"></a>
|
||||
<a id="org13367ca"></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" >}}
|
||||
|
||||
@ -2699,7 +2699,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="org3196916"></a>
|
||||
<a id="orgdc8007d"></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" >}}
|
||||
|
||||
@ -2708,7 +2708,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="org1ec15cf"></a>
|
||||
<a id="org1575595"></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" >}}
|
||||
|
||||
@ -2727,7 +2727,7 @@ Thus, independent controllers for each joint may be suitable for this topology.
|
||||
|
||||
### Direct Force Control {#direct-force-control}
|
||||
|
||||
<a id="orgbb2ac3a"></a>
|
||||
<a id="org53ade2e"></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" >}}
|
||||
|
||||
@ -2818,7 +2818,7 @@ The impedance of the system may be found from the Laplace transform of the above
|
||||
|
||||
</div>
|
||||
|
||||
<a id="org6bbc35b"></a>
|
||||
<a id="orgfca539d"></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" >}}
|
||||
|
||||
@ -2877,7 +2877,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="orga15adbe"></a>
|
||||
<a id="orgf8596ce"></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" >}}
|
||||
|
||||
@ -2915,4 +2915,4 @@ However, note that for a good performance, an accurate model of the system is re
|
||||
|
||||
## Bibliography {#bibliography}
|
||||
|
||||
<a id="org83723e5"></a>Taghirad, Hamid. 2013. _Parallel Robots : Mechanics and Control_. Boca Raton, FL: CRC Press.
|
||||
<a id="orge267b8c"></a>Taghirad, Hamid. 2013. _Parallel Robots : Mechanics and Control_. Boca Raton, FL: CRC Press.
|
||||
|
@ -8,14 +8,112 @@ Tags
|
||||
:
|
||||
|
||||
|
||||
## The Jacobian Matrix for Parallel manipulators {#the-jacobian-matrix-for-parallel-manipulators}
|
||||
## Jacobian Matrices of a Parallel Manipulator {#jacobian-matrices-of-a-parallel-manipulator}
|
||||
|
||||
How to derive the Jacobian matrix is well explained in chapter 4 of ([Taghirad 2013](#org6a92616)) ([notes]({{< relref "taghirad13_paral" >}})).
|
||||
It is also well defined in ([Merlet 2006](#org6d3f9cc)).
|
||||
From ([Taghirad 2013](#org1eb570f)):
|
||||
|
||||
> The Jacobian matrix not only reveals the **relation between the joint variable velocities of a parallel manipulator to the moving platform linear and angular velocities**, it also constructs the transformation needed to find the **actuator forces from the forces and moments acting on the moving platform**.
|
||||
|
||||
([Merlet 2006](#org77b3718))
|
||||
|
||||
|
||||
## Computing the Jacobian Matrix {#computing-the-jacobian-matrix}
|
||||
|
||||
How to derive the Jacobian matrix is well explained in chapter 4 of ([Taghirad 2013](#org1eb570f)) ([notes]({{< relref "taghirad13_paral" >}})).
|
||||
|
||||
Consider parallel manipulator shown in Figure [1](#orgf2877e3) (it represents a Stewart platform).
|
||||
|
||||
Kinematic loop closures are:
|
||||
|
||||
\begin{equation}
|
||||
{}^A\bm{O}\_B = {}^A\bm{a}\_i + l\_i \hat{\bm{s}}\_i + {}^A\bm{b}\_i
|
||||
\end{equation}
|
||||
|
||||
Which can be written as:
|
||||
|
||||
\begin{equation}
|
||||
{}^A\bm{p} = {}^A\bm{a}\_i + l\_i {}^A\hat{\bm{s}}\_i + {}^A\bm{R}\_B {}^B\bm{b}\_i
|
||||
\end{equation}
|
||||
|
||||
with
|
||||
|
||||
- \\({}^A\bm{p} = {}^A\bm{O}\_B\\) the position vector of the moving platform w.r.t. frame \\(\\{\bm{A}\\}\\)
|
||||
- \\({}^A\bm{R}\_B\\) the rotation matrix of the moving platform
|
||||
- \\({}^A\bm{a}\_i\\) the position vector of the \\(i\\)'th limb of the fixed platform w.r.t. frame \\(\\{\bm{A}\\}\\)
|
||||
- \\({}^B\bm{b}\_i\\) the position vector of the \\(i\\)'th limb of the moving platform w.r.t. frame \\(\\{\bm{B}\\}\\)
|
||||
- \\(\bm{\hat{s}}\_i\\) the limb unit vector
|
||||
- \\(l\_i\\) is the limb length
|
||||
|
||||
By taking the time derivative, we obtain the following **Velocity Loop Closures**:
|
||||
|
||||
\begin{equation}
|
||||
{}^A\hat{\bm{s}}\_i {}^A\bm{v}\_p + ({}^A\bm{b}\_i \times \hat{\bm{s}}\_i) {}^A\bm{\omega} = \dot{l}\_i \label{eq:velocity\_loop\_closure}
|
||||
\end{equation}
|
||||
|
||||
<a id="orgf2877e3"></a>
|
||||
|
||||
{{< figure src="/ox-hugo/jacobian_geometry.png" caption="Figure 1: Example of parallel manipulator with defined frames and vectors" >}}
|
||||
|
||||
|
||||
## Velocities of joints and of moving platform {#velocities-of-joints-and-of-moving-platform}
|
||||
|
||||
The Jacobian matrix links the joint variable velocities to the moving platform linear and angular velocities.
|
||||
|
||||
\begin{equation}
|
||||
\dot{\bm{q}} = \bm{J} \dot{\bm{\mathcal{X}}}
|
||||
\end{equation}
|
||||
|
||||
with \\(\bm{q} = \left[ q\_1, q\_2, \ldots, q\_m \right]^T\\) the vector of actuated joint coordinates (linear displacement of an actuator prismatic joint or angular rotation of an actuated revolute joint) and \\(\bm{\mathcal{X}} = \left[ x\_1, x\_2, \ldots, x\_n \right]^T\\) the vector of moving platform motion variables (position or orientation).
|
||||
|
||||
From equation \eqref{eq:velocity_loop_closure}, we have:
|
||||
|
||||
\begin{equation}
|
||||
\bm{J} = \begin{bmatrix}
|
||||
{{}^A\hat{\bm{s}}\_1}^T & ({}^A\bm{b}\_1 \times {}^A\hat{\bm{s}}\_1)^T \\\\\\
|
||||
{{}^A\hat{\bm{s}}\_2}^T & ({}^A\bm{b}\_2 \times {}^A\hat{\bm{s}}\_2)^T \\\\\\
|
||||
{{}^A\hat{\bm{s}}\_3}^T & ({}^A\bm{b}\_3 \times {}^A\hat{\bm{s}}\_3)^T \\\\\\
|
||||
{{}^A\hat{\bm{s}}\_4}^T & ({}^A\bm{b}\_4 \times {}^A\hat{\bm{s}}\_4)^T \\\\\\
|
||||
{{}^A\hat{\bm{s}}\_5}^T & ({}^A\bm{b}\_5 \times {}^A\hat{\bm{s}}\_5)^T \\\\\\
|
||||
{{}^A\hat{\bm{s}}\_6}^T & ({}^A\bm{b}\_6 \times {}^A\hat{\bm{s}}\_6)^T
|
||||
\end{bmatrix}
|
||||
\end{equation}
|
||||
|
||||
And therefore \\(\bm{J}\\) then **depends only** on:
|
||||
|
||||
- \\({}^A\hat{\bm{s}}\_i\\) the orientation of the limbs
|
||||
- \\({}^A\bm{b}\_i\\) the position of the joints with respect to \\(O\_B\\) and express in \\(\\{\bm{A}\\}\\).
|
||||
|
||||
For the platform in Figure [1](#orgf2877e3), we have:
|
||||
|
||||
\begin{equation}
|
||||
\begin{bmatrix} \dot{l}\_1 \\ \dot{l}\_2 \\ \dot{l}\_3 \\ \dot{l}\_4 \\ \dot{l}\_5 \\ \dot{l}\_6 \end{bmatrix} =
|
||||
\begin{bmatrix}
|
||||
{{}^A\hat{\bm{s}}\_1}^T & ({}^A\bm{b}\_1 \times {}^A\hat{\bm{s}}\_1)^T \\\\\\
|
||||
{{}^A\hat{\bm{s}}\_2}^T & ({}^A\bm{b}\_2 \times {}^A\hat{\bm{s}}\_2)^T \\\\\\
|
||||
{{}^A\hat{\bm{s}}\_3}^T & ({}^A\bm{b}\_3 \times {}^A\hat{\bm{s}}\_3)^T \\\\\\
|
||||
{{}^A\hat{\bm{s}}\_4}^T & ({}^A\bm{b}\_4 \times {}^A\hat{\bm{s}}\_4)^T \\\\\\
|
||||
{{}^A\hat{\bm{s}}\_5}^T & ({}^A\bm{b}\_5 \times {}^A\hat{\bm{s}}\_5)^T \\\\\\
|
||||
{{}^A\hat{\bm{s}}\_6}^T & ({}^A\bm{b}\_6 \times {}^A\hat{\bm{s}}\_6)^T
|
||||
\end{bmatrix}
|
||||
\begin{bmatrix} {}^Av\_x \\ {}^Av\_y \\ {}^Av\_z \\ {}^A\omega\_x \\ {}^A\omega\_y \\ {}^A\omega\_z \end{bmatrix}
|
||||
\end{equation}
|
||||
|
||||
|
||||
## Static Forces in Parallel Manipulators {#static-forces-in-parallel-manipulators}
|
||||
|
||||
The **Jacobian matrix** constructs the **transformation needed to find the actuator forces** \\(\bm{\tau}\\) **from the wrench acting on the moving platform** \\(\bm{\mathcal{F}}\\):
|
||||
|
||||
\begin{equation}
|
||||
\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 at the point \\(\bm{O}\_B\\).
|
||||
|
||||
Note that it is here assumed that the forces are static and **along the limb axis** \\(\hat{\bm{s}}\_i\\).
|
||||
|
||||
|
||||
## Bibliography {#bibliography}
|
||||
|
||||
<a id="org6d3f9cc"></a>Merlet, Jean-Pierre. 2006. “Jacobian, Manipulability, Condition Number, and Accuracy of Parallel Robots.”
|
||||
<a id="org77b3718"></a>Merlet, Jean-Pierre. 2006. “Jacobian, Manipulability, Condition Number, and Accuracy of Parallel Robots.”
|
||||
|
||||
<a id="org6a92616"></a>Taghirad, Hamid. 2013. _Parallel Robots : Mechanics and Control_. Boca Raton, FL: CRC Press.
|
||||
<a id="org1eb570f"></a>Taghirad, Hamid. 2013. _Parallel Robots : Mechanics and Control_. Boca Raton, FL: CRC Press.
|
||||
|
BIN
static/ox-hugo/jacobian_geometry.png
Normal file
BIN
static/ox-hugo/jacobian_geometry.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 47 KiB |
Loading…
Reference in New Issue
Block a user