Add Micro-station model
This commit is contained in:
538
phd-thesis.org
538
phd-thesis.org
@@ -2489,8 +2489,28 @@ First, a /response model/ is obtained, which corresponds to a set of frequency r
|
||||
From this response model, the modal model can be computed, which consists of two matrices: one containing the natural frequencies and damping factors of the considered modes, and another describing the mode shapes.
|
||||
This modal model can then be used to tune the spatial model (i.e. the multi-body model), that is, to tune the mass of the considered solid bodies and the springs and dampers connecting the solid bodies.
|
||||
|
||||
#+begin_src latex :file modal_vibration_analysis_procedure.pdf
|
||||
\begin{tikzpicture}
|
||||
\node[block, inner sep = 8pt, align=center] (1) {Description\\of structure};
|
||||
\node[block, inner sep = 8pt, align=center, left=1.0 of 1] (2) {Vibration\\Modes};
|
||||
\node[block, inner sep = 8pt, align=center, left=1.0 of 2] (3) {Response\\Levels};
|
||||
|
||||
\draw[<->] (1) -- (2);
|
||||
\draw[<->] (2) -- (3);
|
||||
|
||||
\node[above] (labelt) at (1.north) {Spatial Model};
|
||||
\node[] at (2|-labelt) {Modal Model};
|
||||
\node[] at (3|-labelt) {Response Model};
|
||||
|
||||
\node[align = center, font=\tiny, below] (labelb) at (1.south) {Mass\\Stiffness\\Damping};
|
||||
\node[align = center, font=\tiny] at (2|-labelb) {Natural Frequencies\\Mode Shapes\\};
|
||||
\node[align = center, font=\tiny] at (3|-labelb) {Time Responses\\Frequency Responses\\};
|
||||
\end{tikzpicture}
|
||||
#+end_src
|
||||
|
||||
#+name: fig:modal_vibration_analysis_procedure
|
||||
#+caption: Three models of the same structure. The goal is to tune a spatial model (i.e. mass, stiffness and damping properties) from a response model. The modal model can be used as an intermediate step.
|
||||
#+RESULTS:
|
||||
[[file:figs/modal_vibration_analysis_procedure.png]]
|
||||
|
||||
The measurement setup used to obtain the response model is described in Section ref:sec:modal_meas_setup.
|
||||
@@ -2503,6 +2523,16 @@ The solid body assumption is then verified, validating the use of the multi-body
|
||||
Finally, the modal analysis is performed in Section ref:sec:modal_analysis.
|
||||
This shows how complex the micro-station dynamics is, and the necessity of having a model representing its complex dynamics.
|
||||
|
||||
# #+name: tab:modal_section_matlab_code
|
||||
# #+caption: Report sections and corresponding Matlab files
|
||||
# #+attr_latex: :environment tabularx :width 0.5\linewidth :align lX
|
||||
# #+attr_latex: :center t :booktabs t
|
||||
# | *Sections* | *Matlab File* |
|
||||
# |--------------------------------------+----------------------------|
|
||||
# | Section ref:sec:modal_meas_setup | =modal_1_meas_setup.m= |
|
||||
# | Section ref:sec:modal_frf_processing | =modal_2_frf_processing.m= |
|
||||
# | Section ref:sec:modal_analysis | =modal_3_analysis.m= |
|
||||
|
||||
*** Measurement Setup
|
||||
<<sec:modal_meas_setup>>
|
||||
**** Introduction :ignore:
|
||||
@@ -2763,8 +2793,43 @@ To validate this reduction of acrshort:dof and the solid body assumption, the fr
|
||||
Let us consider the schematic shown in Figure ref:fig:modal_local_to_global_coordinates where the motion of a solid body is measured at 4 distinct locations (in $x$, $y$ and $z$ directions).
|
||||
The goal here is to link these $4 \times 3 = 12$ measurements to the 6 acrshort:dof of the solid body expressed in the frame $\{O\}$.
|
||||
|
||||
#+begin_src latex :file modal_local_to_global_coordinates.pdf
|
||||
\newcommand\irregularcircle[2]{% radius, irregularity
|
||||
\pgfextra {\pgfmathsetmacro\len{(#1)+rand*(#2)}}
|
||||
+(0:\len pt)
|
||||
\foreach \a in {10,20,...,350}{
|
||||
\pgfextra {\pgfmathsetmacro\len{(#1)+rand*(#2)}}
|
||||
-- +(\a:\len pt)
|
||||
} -- cycle
|
||||
}
|
||||
\begin{tikzpicture}
|
||||
\draw[rounded corners=1mm, fill=blue!30!white] (0, 0) \irregularcircle{3cm}{1mm};
|
||||
|
||||
\node[] (origin) at (0, 0) {$\bullet$};
|
||||
\begin{scope}[shift={(origin)}]
|
||||
\def\axissize{0.8cm}
|
||||
\draw[->] (0, 0) -- ++(\axissize, 0) node[above left]{$x$};
|
||||
\draw[->] (0, 0) -- ++(0, \axissize) node[below right]{$y$};
|
||||
\draw[fill, color=black] (0, 0) circle (0.05*\axissize);
|
||||
\node[draw, circle, inner sep=0pt, minimum size=0.4*\axissize, label=left:$z$] (yaxis) at (0, 0){};
|
||||
\node[below right] at (0, 0){$\{O\}$};
|
||||
\end{scope}
|
||||
|
||||
\coordinate[] (p1) at (-1.5, -1.5);
|
||||
\coordinate[] (p2) at (-1.5, 1.5);
|
||||
\coordinate[] (p3) at ( 1.5, 1.5);
|
||||
\coordinate[] (p4) at ( 1.5, -1.5);
|
||||
|
||||
\draw[->] (p1)node[]{$\bullet$}node[above]{$\vec{p}_1$} -- ++( 1 , 0.1)node[right]{$\delta \vec{p}_1$};
|
||||
\draw[->] (p2)node[]{$\bullet$}node[above]{$\vec{p}_2$} -- ++(-0.5,-0.4)node[below]{$\delta \vec{p}_2$};
|
||||
\draw[->] (p3)node[]{$\bullet$}node[above]{$\vec{p}_3$} -- ++(-0.8,-0.1)node[below]{$\delta \vec{p}_3$};
|
||||
\draw[->] (p4)node[]{$\bullet$}node[above]{$\vec{p}_4$} -- ++( 0.5, 0.2)node[below]{$\delta \vec{p}_4$};
|
||||
\end{tikzpicture}
|
||||
#+end_src
|
||||
|
||||
#+name: fig:modal_local_to_global_coordinates
|
||||
#+caption: Schematic of the measured motions of a solid body
|
||||
#+RESULTS:
|
||||
[[file:figs/modal_local_to_global_coordinates.png]]
|
||||
|
||||
The motion of the rigid body of figure ref:fig:modal_local_to_global_coordinates can be described by its displacement $\vec{\delta}p = [\delta p_x,\ \delta p_y,\ \delta p_z]$ and (small) rotations $[\delta \Omega_x,\ \delta \Omega_y,\ \delta \Omega_z]$ with respect to the reference frame $\{O\}$.
|
||||
@@ -2878,7 +2943,7 @@ The acrshort:mif is applied to the $n\times p$ acrshort:frf matrix where $n$ is
|
||||
|
||||
The complex modal indication function is defined in equation eqref:eq:modal_cmif where the diagonal matrix $\Sigma$ is obtained from a acrlong:svd of the acrshort:frf matrix as shown in equation eqref:eq:modal_svd.
|
||||
\begin{equation} \label{eq:modal_cmif}
|
||||
[CMIF(\omega)]_{p\times p} = [\Sigma(\omega)]_{p\times n}^T [\Sigma(\omega)]_{n\times p}
|
||||
[CMIF(\omega)]_{p\times p} = [\Sigma(\omega)]_{p\times n}^{\intercal} [\Sigma(\omega)]_{n\times p}
|
||||
\end{equation}
|
||||
|
||||
\begin{equation} \label{eq:modal_svd}
|
||||
@@ -2978,7 +3043,7 @@ The modal parameter extraction is made using a proprietary software[fn:modal_4].
|
||||
For each mode $r$ (from $1$ to the number of considered modes $m=16$), it outputs the frequency $\omega_r$, the damping ratio $\xi_r$, the eigenvectors $\{\phi_{r}\}$ (vector of complex numbers with a size equal to the number of measured acrshort:dof $n=69$, see equation eqref:eq:modal_eigenvector) and a scaling factor $a_r$.
|
||||
|
||||
\begin{equation}\label{eq:modal_eigenvector}
|
||||
\{\phi_i\} = \begin{Bmatrix} \phi_{i, 1_x} & \phi_{i, 1_y} & \phi_{i, 1_z} & \phi_{i, 2_x} & \dots & \phi_{i, 23_z} \end{Bmatrix}^T
|
||||
\{\phi_i\} = \begin{Bmatrix} \phi_{i, 1_x} & \phi_{i, 1_y} & \phi_{i, 1_z} & \phi_{i, 2_x} & \dots & \phi_{i, 23_z} \end{Bmatrix}^{\intercal}
|
||||
\end{equation}
|
||||
|
||||
The eigenvalues $s_r$ and $s_r^*$ can then be computed from equation eqref:eq:modal_eigenvalues.
|
||||
@@ -3005,7 +3070,7 @@ In order to synthesize the full acrshort:frf matrix, the eigenvectors $\phi_r$ a
|
||||
The full acrshort:frf matrix $\mathbf{H}_{\text{syn}}$ can be obtained using eqref:eq:modal_synthesized_frf.
|
||||
|
||||
\begin{equation}\label{eq:modal_synthesized_frf}
|
||||
[\mathbf{H}_{\text{syn}}(\omega)]_{n\times n} = [\Phi]_{n\times2m} [\mathbf{H}_{\text{mod}}(\omega)]_{2m\times2m} [\Phi]_{2m\times n}^T
|
||||
[\mathbf{H}_{\text{syn}}(\omega)]_{n\times n} = [\Phi]_{n\times2m} [\mathbf{H}_{\text{mod}}(\omega)]_{2m\times2m} [\Phi]_{2m\times n}^{\intercal}
|
||||
\end{equation}
|
||||
|
||||
With $\mathbf{H}_{\text{mod}}(\omega)$ a diagonal matrix representing the response of the different modes eqref:eq:modal_modal_resp.
|
||||
@@ -3086,10 +3151,10 @@ To validate the accuracy of the micro-station model, "real world" experiments ar
|
||||
|
||||
The micro-station consists of 4 stacked positioning stages (Figure ref:fig:ustation_cad_view).
|
||||
From bottom to top, the stacked stages are the translation stage $D_y$, the tilt stage $R_y$, the rotation stage (Spindle) $R_z$ and the positioning hexapod.
|
||||
Such a stacked architecture allows high mobility, but the overall stiffness is reduced, and the dynamics is very complex. complex dynamics.
|
||||
Such a stacked architecture allows high mobility, but the overall stiffness is reduced, and the dynamics is very complex.
|
||||
|
||||
#+name: fig:ustation_cad_view
|
||||
#+caption: CAD view of the micro-station with the translation stage (in blue), tilt stage (in red), rotation stage (in yellow) and positioning hexapod (in purple). On top of these four stages, a solid part (shown in green) will be replaced by the stabilization stage.
|
||||
#+caption: CAD view of the micro-station with the translation stage (in blue), tilt stage (in red), rotation stage (in yellow) and positioning hexapod (in purple).
|
||||
#+attr_latex: :width \linewidth
|
||||
[[file:figs/ustation_cad_view.png]]
|
||||
|
||||
@@ -3103,17 +3168,17 @@ The "controlled" DoF of each stage (for instance the $D_y$ direction for the tra
|
||||
**** Motion Stages
|
||||
<<ssec:ustation_stages>>
|
||||
|
||||
***** Translation Stage
|
||||
****** Translation Stage
|
||||
|
||||
The translation stage is used to position and scan the sample laterally with respect to the X-ray beam.
|
||||
|
||||
A linear motor was first used to enable fast and accurate scans.
|
||||
It was later replaced with a stepper motor and lead-screw, as the feedback control used for the linear motor was unreliable[fn:ustation_12].
|
||||
It was later replaced with a stepper motor and lead-screw, as the feedback control used for the linear motor was unreliable[fn:ustation_11].
|
||||
An optical linear encoder is used to measure the stage motion and for controlling the position.
|
||||
|
||||
Four cylindrical bearings[fn:ustation_4] are used to guide the motion (i.e. minimize the parasitic motions) and have high stiffness.
|
||||
|
||||
***** Tilt Stage
|
||||
****** Tilt Stage
|
||||
|
||||
The tilt stage is guided by four linear motion guides[fn:ustation_1] which are placed such that the center of rotation coincide with the X-ray beam.
|
||||
Each linear guide is very stiff in radial directions such that the only DoF with low stiffness is in $R_y$.
|
||||
@@ -3139,14 +3204,14 @@ To precisely control the $R_y$ angle, a stepper motor and two optical encoders a
|
||||
[[file:figs/ustation_ry_stage.png]]
|
||||
#+end_minipage
|
||||
|
||||
***** Spindle
|
||||
****** Spindle
|
||||
|
||||
Then, a rotation stage is used for tomography experiments.
|
||||
It is composed of an air bearing spindle[fn:ustation_2], whose angular position is controlled with a 3 phase synchronous motor based on the reading of 4 optical encoders.
|
||||
|
||||
Additional rotary unions and slip-rings are used to be able to pass electrical signals, fluids and gazes through the rotation stage.
|
||||
|
||||
***** Micro-Hexapod
|
||||
****** Micro-Hexapod
|
||||
|
||||
Finally, a Stewart platform[fn:ustation_3] is used to position the sample.
|
||||
It includes a DC motor and an optical linear encoders in each of the six struts.
|
||||
@@ -3172,7 +3237,7 @@ It can also be used to precisely position the PoI vertically with respect to the
|
||||
|
||||
**** Mathematical description of a rigid body motion
|
||||
<<ssec:ustation_motion_description>>
|
||||
***** Introduction :ignore:
|
||||
****** Introduction :ignore:
|
||||
|
||||
In this section, mathematical tools[fn:ustation_6] that are used to describe the motion of positioning stages are introduced.
|
||||
|
||||
@@ -3180,7 +3245,7 @@ First, the tools to describe the pose of a solid body (i.e. it's position and or
|
||||
The motion induced by a positioning stage is described by transformation matrices.
|
||||
Finally, the motions of all stacked stages are combined, and the sample's motion is computed from each stage motion.
|
||||
|
||||
***** Spatial motion representation
|
||||
****** Spatial motion representation
|
||||
|
||||
The /pose/ of a solid body relative to a specific frame can be described by six independent parameters.
|
||||
Three parameters are typically used to describe its position, and three other parameters describe its orientation.
|
||||
@@ -3222,14 +3287,10 @@ The /orientation/ of a rigid body is the same at all its points (by definition).
|
||||
Hence, the orientation of a rigid body can be viewed as that of a moving frame attached to the rigid body.
|
||||
It can be represented in several different ways: the rotation matrix, the screw axis representation, and the Euler angles are common descriptions.
|
||||
|
||||
The rotation matrix ${}^A\bm{R}_B$ is a $3 \times 3$ matrix containing the Cartesian unit vectors of frame $\{\bm{B}\}$ represented in frame $\{\bm{A}\}$ eqref:eq:ustation_rotation_matrix.
|
||||
The rotation matrix ${}^A\bm{R}_B$ is a $3 \times 3$ matrix containing the Cartesian unit vectors $[{}^A\hat{\bm{x}}_B,\ {}^A\hat{\bm{y}}_B,\ {}^A\hat{\bm{z}}_B]$ of frame $\{\bm{B}\}$ represented in frame $\{\bm{A}\}$ eqref:eq:ustation_rotation_matrix.
|
||||
|
||||
\begin{equation}\label{eq:ustation_rotation_matrix}
|
||||
{}^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}
|
||||
\end{bmatrix}
|
||||
{}^A\bm{R}_B = \left[ {}^A\hat{\bm{x}}_B | {}^A\hat{\bm{y}}_B | {}^A\hat{\bm{z}}_B \right]
|
||||
\end{equation}
|
||||
|
||||
Consider a pure rotation of a rigid body ($\{\bm{A}\}$ and $\{\bm{B}\}$ are coincident at their origins, as shown in Figure ref:fig:ustation_rotation).
|
||||
@@ -3245,7 +3306,7 @@ For rotations along $x$, $y$ or $z$ axis, the formulas of the corresponding rota
|
||||
\begin{align}
|
||||
\bm{R}_x(\theta_x) &= \begin{bmatrix} 1 & 0 & 0 \\ 0 & \cos(\theta_x) & -\sin(\theta_x) \\ 0 & \sin(\theta_x) & \cos(\theta_x) \end{bmatrix} \\
|
||||
\bm{R}_y(\theta_y) &= \begin{bmatrix} \cos(\theta_y) & 0 & \sin(\theta_y) \\ 0 & 1 & 0 \\ -\sin(\theta_y) & 0 & \cos(\theta_y) \end{bmatrix} \\
|
||||
\bm{R}_z(\theta_z) &= \begin{bmatrix} \cos(\theta_z) & -\sin(\theta_z) & 0 \\ \sin(\theta_z) & \cos(\theta_x) & 0 \\ 0 & 0 & 1 \end{bmatrix}
|
||||
\bm{R}_z(\theta_z) &= \begin{bmatrix} \cos(\theta_z) & -\sin(\theta_z) & 0 \\ \sin(\theta_z) & \cos(\theta_z) & 0 \\ 0 & 0 & 1 \end{bmatrix}
|
||||
\end{align}
|
||||
\end{subequations}
|
||||
|
||||
@@ -3266,7 +3327,7 @@ Such rotation can be parameterized by three Euler angles $(\alpha,\ \beta,\ \gam
|
||||
\end{align}
|
||||
\end{subequations}
|
||||
|
||||
***** Motion of a Rigid Body
|
||||
****** Motion of a Rigid Body
|
||||
|
||||
Since the relative positions of a rigid body with respect to a moving frame $\{B\}$ attached to it are fixed for all time, it is sufficient to know the position of the origin of the frame $O_B$ and the orientation of the frame $\{B\}$ with respect to the fixed frame $\{A\}$, to represent the position of any point $P$ in the space.
|
||||
|
||||
@@ -3335,7 +3396,7 @@ Another key advantage of homogeneous transformation is the easy inverse transfor
|
||||
{}^B\bm{T}_A = {}^A\bm{T}_B^{-1} =
|
||||
\left[ \begin{array}{ccc|c}
|
||||
& & & \\
|
||||
& {}^A\bm{R}_B^T & & -{}^A \bm{R}_B^T {}^AP_{O_B} \\
|
||||
& {}^A\bm{R}_B^{\intercal} & & -{}^A \bm{R}_B^{\intercal} {}^AP_{O_B} \\
|
||||
& & & \cr
|
||||
\hline
|
||||
0 & 0 & 0 & 1 \\
|
||||
@@ -3377,8 +3438,9 @@ The homogeneous transformation matrix corresponding to the micro-station $\bm{T}
|
||||
|
||||
$\bm{T}_{\mu\text{-station}}$ represents the pose of the sample (supposed to be rigidly fixed on top of the positioning-hexapod) with respect to the granite.
|
||||
|
||||
If the transformation matrices of the individual stages are each representing a perfect motion (i.e. the stages are supposed to have no parasitic motion), $\bm{T}_{\mu\text{-station}}$ then represent the pose setpoint of the sample with respect to the granite.
|
||||
If the transformation matrices of the individual stages are each representing a perfect motion (i.e. the stages are supposed to have no parasitic motion), $\bm{T}_{\mu\text{-station}}$ then represents the pose setpoint of the sample with respect to the granite.
|
||||
The transformation matrices for the translation stage, tilt stage, spindle, and positioning hexapod can be written as shown in Equation eqref:eq:ustation_transformation_matrices_stages.
|
||||
The setpoints are $D_y$ for the translation stage, $\theta_y$ for the tilt-stage, $\theta_z$ for the spindle, $[D_{\mu x},\ D_{\mu y}, D_{\mu z}]$ for the micro-hexapod translations and $[\theta_{\mu x},\ \theta_{\mu y}, \theta_{\mu z}]$ for the micro-hexapod rotations.
|
||||
|
||||
\begin{equation}\label{eq:ustation_transformation_matrices_stages}
|
||||
\begin{align}
|
||||
@@ -3437,7 +3499,7 @@ Joints are used to impose kinematic constraints between solid bodies and to spec
|
||||
External forces can be used to model disturbances, and "sensors" can be used to measure the relative pose between two defined frames.
|
||||
|
||||
#+name: fig:ustation_simscape_stage_example
|
||||
#+caption: Example of a stage (here the tilt-stage) represented in the multi-body model software (Simscape). It is composed of two solid bodies connected by a 6-DoF joint. One joint DoF (here the tilt angle) can be imposed, the other DoFs are represented by springs and dampers. Additional disturbances forces for all DoF can be included
|
||||
#+caption: Example of a stage (here the tilt-stage) represented in the multi-body model software (Simscape). It is composed of two solid bodies connected by a 6-DoF joint. One joint DoF (here the tilt angle) can be imposed, the other DoFs are represented by springs and dampers. Additional disturbing forces for all DoF can be included
|
||||
[[file:figs/ustation_simscape_stage_example.png]]
|
||||
|
||||
Therefore, the micro-station is modeled by several solid bodies connected by joints.
|
||||
@@ -3570,7 +3632,7 @@ Similar to what is done for the accelerometers, a Jacobian matrix $\bm{J}_F$ is
|
||||
The equivalent forces and torques applied at center of $\{\mathcal{X}\}$ are then computed using eqref:eq:ustation_compute_cart_force.
|
||||
|
||||
\begin{equation}\label{eq:ustation_compute_cart_force}
|
||||
F_{\mathcal{X}} = \bm{J}_F^t \cdot F_{\mathcal{L}}
|
||||
F_{\mathcal{X}} = \bm{J}_F^{\intercal} \cdot F_{\mathcal{L}}
|
||||
\end{equation}
|
||||
|
||||
Using the two Jacobian matrices, the FRF from the 10 hammer impacts to the 12 accelerometer outputs can be converted to the FRF from 6 forces/torques applied at the origin of frame $\{\mathcal{X}\}$ to the 6 linear/angular accelerations of the top platform expressed with respect to $\{\mathcal{X}\}$.
|
||||
@@ -3604,8 +3666,8 @@ Considering the complexity of the micro-station compliance dynamics, the model c
|
||||
|
||||
The goal of this section is to obtain a realistic representation of disturbances affecting the micro-station.
|
||||
These disturbance sources are then used during time domain simulations to accurately model the micro-station behavior.
|
||||
The focus on stochastic disturbances because, in principle, it is possible to calibrate the repeatable part of disturbances.
|
||||
Such disturbances include ground motions and vibrations induces by scanning the translation stage and the spindle.
|
||||
The focus is on stochastic disturbances because, in principle, it is possible to calibrate the repeatable part of disturbances.
|
||||
Such disturbances include ground motions and vibrations induce by scanning the translation stage and the spindle.
|
||||
|
||||
In the multi-body model, stage vibrations are modeled as internal forces applied in the stage joint.
|
||||
In practice, disturbance forces cannot be directly measured.
|
||||
@@ -3616,16 +3678,16 @@ Finally, the obtained disturbance sources are compared in Section ref:ssec:ustat
|
||||
|
||||
**** Disturbance measurements
|
||||
<<ssec:ustation_disturbances_meas>>
|
||||
***** Introduction :ignore:
|
||||
****** Introduction :ignore:
|
||||
In this section, ground motion is directly measured using geophones.
|
||||
Vibrations induced by scanning the translation stage and the spindle are also measured using dedicated setups.
|
||||
|
||||
The tilt stage and the micro-hexapod also have positioning errors; however, they are not modeled here because these two stages are only used for pre-positioning and not for scanning.
|
||||
Therefore, from a control perspective, they are not important.
|
||||
|
||||
***** Ground Motion
|
||||
****** Ground Motion
|
||||
|
||||
The ground motion was measured by using a sensitive 3-axis geophone[fn:ustation_11] placed on the ground.
|
||||
The ground motion was measured by using a sensitive 3-axis geophone shown in Figure ref:fig:ustation_geophone_picture placed on the ground.
|
||||
The generated voltages were recorded with a high resolution DAC, and converted to displacement using the Geophone sensitivity transfer function.
|
||||
The obtained ground motion displacement is shown in Figure ref:fig:ustation_ground_disturbance.
|
||||
|
||||
@@ -3645,14 +3707,14 @@ The obtained ground motion displacement is shown in Figure ref:fig:ustation_grou
|
||||
[[file:figs/ustation_geophone_picture.jpg]]
|
||||
#+end_minipage
|
||||
|
||||
***** Ty Stage
|
||||
****** Ty Stage
|
||||
|
||||
To measure the positioning errors of the translation stage, the setup shown in Figure ref:fig:ustation_errors_ty_setup is used.
|
||||
A special optical element (called a "straightness interferometer"[fn:ustation_9]) is fixed on top of the micro-station, while a laser source[fn:ustation_10] and a straightness reflector are fixed on the ground.
|
||||
A similar setup was used to measure the horizontal deviation (i.e. in the $x$ direction), as well as the pitch and yaw errors of the translation stage.
|
||||
|
||||
#+name: fig:ustation_errors_ty_setup
|
||||
#+caption: Experimental setup to measure the flatness (vertical deviation) of the translation stage
|
||||
#+caption: Experimental setup to measure the straightness (vertical deviation) of the translation stage
|
||||
[[file:figs/ustation_errors_ty_setup.png]]
|
||||
|
||||
Six scans were performed between $-4.5\,mm$ and $4.5\,mm$.
|
||||
@@ -3680,7 +3742,7 @@ Similar result is obtained for the $x$ lateral direction.
|
||||
#+end_subfigure
|
||||
#+end_figure
|
||||
|
||||
***** Spindle
|
||||
****** Spindle
|
||||
|
||||
To measure the positioning errors induced by the Spindle, a "Spindle error analyzer"[fn:ustation_7] is used as shown in Figure ref:fig:ustation_rz_meas_lion_setup.
|
||||
A specific target is fixed on top of the micro-station, which consists of two sphere with 1 inch diameter precisely aligned with the spindle rotation axis.
|
||||
@@ -3800,7 +3862,7 @@ The obtained power spectral density of the disturbances are shown in Figure ref:
|
||||
|
||||
The disturbances are characterized by their power spectral densities, as shown in Figure ref:fig:ustation_dist_sources.
|
||||
However, to perform time domain simulations, disturbances must be represented by a time domain signal.
|
||||
To generate stochastic time-domain signals with a specific power spectral densities, the discrete inverse Fourier transform is used, as explained in [[cite:&preumont94_random_vibrat_spect_analy chap. 12.11]].
|
||||
To generate stochastic time-domain signals with a specific power spectral density, the discrete inverse Fourier transform is used, as explained in [[cite:&preumont94_random_vibrat_spect_analy chap. 12.11]].
|
||||
Examples of the obtained time-domain disturbance signals are shown in Figure ref:fig:ustation_dist_sources_time.
|
||||
|
||||
#+name: fig:ustation_dist_sources_time
|
||||
@@ -3864,7 +3926,7 @@ A good correlation with the measurements is observed both for radial errors (Fig
|
||||
#+end_subfigure
|
||||
#+end_figure
|
||||
|
||||
**** Raster Scans with the translation stage
|
||||
**** Scans with the translation stage
|
||||
<<sec:ustation_experiments_ty_scans>>
|
||||
|
||||
A second experiment was performed in which the translation stage was scanned at constant velocity.
|
||||
@@ -4162,7 +4224,7 @@ This is summarized in Figure ref:fig:nhexa_stewart_notations.
|
||||
|
||||
**** Kinematic Analysis
|
||||
<<ssec:nhexa_stewart_platform_kinematics>>
|
||||
***** Loop Closure
|
||||
****** Loop Closure
|
||||
|
||||
The foundation of the kinematic analysis lies in the geometric constraints imposed by each strut, which can be expressed using loop closure equations.
|
||||
For each strut $i$ (illustrated in Figure ref:fig:nhexa_stewart_loop_closure), the loop closure equation eqref:eq:nhexa_loop_closure can be written.
|
||||
@@ -4177,20 +4239,20 @@ This equation links the pose[fn:nhexa_2] variables ${}^A\bm{P}$ and ${}^A\bm{R}_
|
||||
#+caption: Notations to compute the kinematic loop closure
|
||||
[[file:figs/nhexa_stewart_loop_closure.png]]
|
||||
|
||||
***** Inverse Kinematics
|
||||
****** Inverse Kinematics
|
||||
|
||||
The inverse kinematic problem involves determining the required strut lengths $\bm{\mathcal{L}} = \left[ l_1, l_2, \ldots, l_6 \right]^T$ for a desired platform pose $\bm{\mathcal{X}}$ (i.e. position ${}^A\bm{P}$ and orientation ${}^A\bm{R}_B$).
|
||||
The inverse kinematic problem involves determining the required strut lengths $\bm{\mathcal{L}} = \left[ l_1, l_2, \ldots, l_6 \right]^{\intercal}$ for a desired platform pose $\bm{\mathcal{X}}$ (i.e. position ${}^A\bm{P}$ and orientation ${}^A\bm{R}_B$).
|
||||
This problem can be solved analytically using the loop closure equations eqref:eq:nhexa_loop_closure.
|
||||
The obtained strut lengths are given by eqref:eq:nhexa_inverse_kinematics.
|
||||
|
||||
\begin{equation}\label{eq:nhexa_inverse_kinematics}
|
||||
l_i = \sqrt{{}^A\bm{P}^T {}^A\bm{P} + {}^B\bm{b}_i^T {}^B\bm{b}_i + {}^A\bm{a}_i^T {}^A\bm{a}_i - 2 {}^A\bm{P}^T {}^A\bm{a}_i + 2 {}^A\bm{P}^T \left[{}^A\bm{R}_B {}^B\bm{b}_i\right] - 2 \left[{}^A\bm{R}_B {}^B\bm{b}_i\right]^T {}^A\bm{a}_i}
|
||||
l_i = \sqrt{{}^A\bm{P}^{\intercal} {}^A\bm{P} + {}^B\bm{b}_i^{\intercal} {}^B\bm{b}_i + {}^A\bm{a}_i^{\intercal} {}^A\bm{a}_i - 2 {}^A\bm{P}^{\intercal} {}^A\bm{a}_i + 2 {}^A\bm{P}^{\intercal} \left[{}^A\bm{R}_B {}^B\bm{b}_i\right] - 2 \left[{}^A\bm{R}_B {}^B\bm{b}_i\right]^{\intercal} {}^A\bm{a}_i}
|
||||
\end{equation}
|
||||
|
||||
If the position and orientation of the platform lie in the feasible workspace, the solution is unique.
|
||||
While configurations outside this workspace yield complex numbers, this only becomes relevant for large displacements that far exceed the nano-hexapod's operating range.
|
||||
|
||||
***** Forward Kinematics
|
||||
****** Forward Kinematics
|
||||
|
||||
The forward kinematic problem seeks to determine the platform pose $\bm{\mathcal{X}}$ given a set of strut lengths $\bm{\mathcal{L}}$.
|
||||
Unlike inverse kinematics, this presents a significant challenge because it requires solving a system of nonlinear equations.
|
||||
@@ -4203,12 +4265,12 @@ This approximation, which is developed in subsequent sections through the Jacobi
|
||||
|
||||
**** The Jacobian Matrix
|
||||
<<ssec:nhexa_stewart_platform_jacobian>>
|
||||
***** Introduction :ignore:
|
||||
****** Introduction :ignore:
|
||||
|
||||
The Jacobian matrix plays a central role in analyzing the Stewart platform's behavior, providing a linear mapping between the platform and actuator velocities.
|
||||
While the previously derived kinematic relationships are essential for position analysis, the Jacobian enables velocity analysis and forms the foundation for both static and dynamic studies.
|
||||
|
||||
***** Jacobian Computation
|
||||
****** Jacobian Computation
|
||||
|
||||
As discussed in Section ref:ssec:nhexa_stewart_platform_kinematics, the strut lengths $\bm{\mathcal{L}}$ and the platform pose $\bm{\mathcal{X}}$ are related through a system of nonlinear algebraic equations representing the kinematic constraints imposed by the struts.
|
||||
|
||||
@@ -4228,7 +4290,7 @@ By multiplying both sides by ${}^A\hat{\bm{s}}_i$, eqref:eq:nhexa_loop_closure_v
|
||||
{}^A\hat{\bm{s}}_i {}^A\bm{v}_p + \underbrace{{}^A\hat{\bm{s}}_i ({}^A\bm{\omega} \times {}^A\bm{b}_i)}_{=({}^A\bm{b}_i \times {}^A\hat{\bm{s}}_i) {}^A\bm{\omega}} = \dot{l}_i + \underbrace{{}^A\hat{s}_i l_i \left( {}^A\bm{\omega}_i \times {}^A\hat{\bm{s}}_i \right)}_{=0}
|
||||
\end{equation}
|
||||
|
||||
Equation eqref:eq:nhexa_loop_closure_velocity_bis can be rearranged in matrix form to obtain eqref:eq:nhexa_jacobian_velocities, with $\dot{\bm{\mathcal{L}}} = [ \dot{l}_1 \ \dots \ \dot{l}_6 ]^T$ the vector of strut velocities, and $\dot{\bm{\mathcal{X}}} = [{}^A\bm{v}_p ,\ {}^A\bm{\omega}]^T$ the vector of platform velocity and angular velocity.
|
||||
Equation eqref:eq:nhexa_loop_closure_velocity_bis can be rearranged in matrix form to obtain eqref:eq:nhexa_jacobian_velocities, with $\dot{\bm{\mathcal{L}}} = [ \dot{l}_1 \ \dots \ \dot{l}_6 ]^{\intercal}$ the vector of strut velocities, and $\dot{\bm{\mathcal{X}}} = [{}^A\bm{v}_p ,\ {}^A\bm{\omega}]^{\intercal}$ the vector of platform velocity and angular velocity.
|
||||
|
||||
\begin{equation}\label{eq:nhexa_jacobian_velocities}
|
||||
\boxed{\dot{\bm{\mathcal{L}}} = \bm{J} \dot{\bm{\mathcal{X}}}}
|
||||
@@ -4238,21 +4300,21 @@ The matrix $\bm{J}$ is called the Jacobian matrix and is defined by eqref:eq:nhe
|
||||
|
||||
\begin{equation}\label{eq:nhexa_jacobian}
|
||||
\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
|
||||
{{}^A\hat{\bm{s}}_1}^{\intercal} & ({}^A\bm{b}_1 \times {}^A\hat{\bm{s}}_1)^{\intercal} \\
|
||||
{{}^A\hat{\bm{s}}_2}^{\intercal} & ({}^A\bm{b}_2 \times {}^A\hat{\bm{s}}_2)^{\intercal} \\
|
||||
{{}^A\hat{\bm{s}}_3}^{\intercal} & ({}^A\bm{b}_3 \times {}^A\hat{\bm{s}}_3)^{\intercal} \\
|
||||
{{}^A\hat{\bm{s}}_4}^{\intercal} & ({}^A\bm{b}_4 \times {}^A\hat{\bm{s}}_4)^{\intercal} \\
|
||||
{{}^A\hat{\bm{s}}_5}^{\intercal} & ({}^A\bm{b}_5 \times {}^A\hat{\bm{s}}_5)^{\intercal} \\
|
||||
{{}^A\hat{\bm{s}}_6}^{\intercal} & ({}^A\bm{b}_6 \times {}^A\hat{\bm{s}}_6)^{\intercal}
|
||||
\end{bmatrix}
|
||||
\end{equation}
|
||||
|
||||
Therefore, the Jacobian matrix $\bm{J}$ links the rate of change of the strut length to the velocity and angular velocity of the top platform with respect to the fixed base through a set of linear equations.
|
||||
However, $\bm{J}$ needs to be recomputed for every Stewart platform pose because it depends on the actual pose of the manipulator.
|
||||
|
||||
***** Approximate solution to the Forward and Inverse Kinematic problems
|
||||
****** Approximate solution to the Forward and Inverse Kinematic problems
|
||||
|
||||
For small displacements $\delta \bm{\mathcal{X}} = [\delta x, \delta y, \delta z, \delta \theta_x, \delta \theta_y, \delta \theta_z ]^T$ around an operating point $\bm{\mathcal{X}}_0$ (for which the Jacobian was computed), the associated joint displacement $\delta\bm{\mathcal{L}} = [\delta l_1,\,\delta l_2,\,\delta l_3,\,\delta l_4,\,\delta l_5,\,\delta l_6]^T$ can be computed using the Jacobian eqref:eq:nhexa_inverse_kinematics_approximate.
|
||||
For small displacements $\delta \bm{\mathcal{X}} = [\delta x, \delta y, \delta z, \delta \theta_x, \delta \theta_y, \delta \theta_z ]^{\intercal}$ around an operating point $\bm{\mathcal{X}}_0$ (for which the Jacobian was computed), the associated joint displacement $\delta\bm{\mathcal{L}} = [\delta l_1,\,\delta l_2,\,\delta l_3,\,\delta l_4,\,\delta l_5,\,\delta l_6]^{\intercal}$ can be computed using the Jacobian eqref:eq:nhexa_inverse_kinematics_approximate.
|
||||
|
||||
\begin{equation}\label{eq:nhexa_inverse_kinematics_approximate}
|
||||
\boxed{\delta\bm{\mathcal{L}} = \bm{J} \delta\bm{\mathcal{X}}}
|
||||
@@ -4267,7 +4329,7 @@ Similarly, for small joint displacements $\delta\bm{\mathcal{L}}$, it is possibl
|
||||
These two relations solve the forward and inverse kinematic problems for small displacement in a /approximate/ way.
|
||||
While this approximation offers limited value for inverse kinematics, which can be solved analytically, it proves particularly useful for the forward kinematic problem where exact analytical solutions are difficult to obtain.
|
||||
|
||||
***** Range validity of the approximate inverse kinematics
|
||||
****** Range validity of the approximate inverse kinematics
|
||||
|
||||
The accuracy of the Jacobian-based forward kinematics solution was estimated by a simple analysis.
|
||||
For a series of platform positions, the exact strut lengths are computed using the analytical inverse kinematics equation eqref:eq:nhexa_inverse_kinematics.
|
||||
@@ -4284,30 +4346,30 @@ It can be computed once at the rest position and used for both forward and inver
|
||||
#+RESULTS:
|
||||
[[file:figs/nhexa_forward_kinematics_approximate_errors.png]]
|
||||
|
||||
***** Static Forces
|
||||
****** Static Forces
|
||||
|
||||
The static force analysis of the Stewart platform can be performed using the principle of virtual work.
|
||||
This principle states that for a system in static equilibrium, the total virtual work of all forces acting on the system must be zero for any virtual displacement compatible with the system's constraints.
|
||||
|
||||
Let $\bm{f} = [f_1, f_2, \cdots, f_6]^T$ represent the vector of actuator forces applied in each strut, and $\bm{\mathcal{F}} = [\bm{F}, \bm{n}]^T$ denote the external wrench (combined force $\bm{F}$ and torque $\bm{n}$) acting on the mobile platform at point $\bm{O}_B$.
|
||||
Let $\bm{f} = [f_1, f_2, \cdots, f_6]^{\intercal}$ represent the vector of actuator forces applied in each strut, and $\bm{\mathcal{F}} = [\bm{F}, \bm{n}]^{\intercal}$ denote the external wrench (combined force $\bm{F}$ and torque $\bm{n}$) acting on the mobile platform at point $\bm{O}_B$.
|
||||
The virtual work $\delta W$ consists of two contributions:
|
||||
- The work performed by the actuator forces through virtual strut displacements $\delta \bm{\mathcal{L}}$: $\bm{f}^T \delta \bm{\mathcal{L}}$
|
||||
- The work performed by the external wrench through virtual platform displacements $\delta \bm{\mathcal{X}}$: $-\bm{\mathcal{F}}^T \delta \bm{\mathcal{X}}$
|
||||
- The work performed by the actuator forces through virtual strut displacements $\delta \bm{\mathcal{L}}$: $\bm{f}^{\intercal} \delta \bm{\mathcal{L}}$
|
||||
- The work performed by the external wrench through virtual platform displacements $\delta \bm{\mathcal{X}}$: $-\bm{\mathcal{F}}^{\intercal} \delta \bm{\mathcal{X}}$
|
||||
|
||||
Thus, the principle of virtual work can be expressed as:
|
||||
\begin{equation}
|
||||
\delta W = \bm{f}^T \delta \bm{\mathcal{L}} - \bm{\mathcal{F}}^T \delta \bm{\mathcal{X}} = 0
|
||||
\delta W = \bm{f}^{\intercal} \delta \bm{\mathcal{L}} - \bm{\mathcal{F}}^{\intercal} \delta \bm{\mathcal{X}} = 0
|
||||
\end{equation}
|
||||
|
||||
Using the Jacobian relationship that links virtual displacements eqref:eq:nhexa_inverse_kinematics_approximate, this equation becomes:
|
||||
\begin{equation}
|
||||
\left( \bm{f}^T \bm{J} - \bm{\mathcal{F}}^T \right) \delta \bm{\mathcal{X}} = 0
|
||||
\left( \bm{f}^{\intercal} \bm{J} - \bm{\mathcal{F}}^{\intercal} \right) \delta \bm{\mathcal{X}} = 0
|
||||
\end{equation}
|
||||
|
||||
Because this equation must hold for any virtual displacement $\delta \bm{\mathcal{X}}$, the force mapping relationships eqref:eq:nhexa_jacobian_forces can be derived.
|
||||
|
||||
\begin{equation}\label{eq:nhexa_jacobian_forces}
|
||||
\bm{f}^T \bm{J} - \bm{\mathcal{F}}^T = 0 \quad \Rightarrow \quad \boxed{\bm{\mathcal{F}} = \bm{J}^T \bm{f}} \quad \text{and} \quad \boxed{\bm{f} = \bm{J}^{-T} \bm{\mathcal{F}}}
|
||||
\bm{f}^{\intercal} \bm{J} - \bm{\mathcal{F}}^{\intercal} = 0 \quad \Rightarrow \quad \boxed{\bm{\mathcal{F}} = \bm{J}^{\intercal} \bm{f}} \quad \text{and} \quad \boxed{\bm{f} = \bm{J}^{-T} \bm{\mathcal{F}}}
|
||||
\end{equation}
|
||||
|
||||
These equations establish that the transpose of the Jacobian matrix maps actuator forces to platform forces and torques, while its inverse transpose maps platform forces and torques to required actuator forces.
|
||||
@@ -4331,14 +4393,14 @@ These individual relationships can be combined into a matrix form using the diag
|
||||
By applying the force mapping relationships eqref:eq:nhexa_jacobian_forces derived in the previous section and the Jacobian relationship for small displacements eqref:eq:nhexa_forward_kinematics_approximate, the relationship between applied wrench $\bm{\mathcal{F}}$ and resulting platform displacement $\delta \bm{\mathcal{X}}$ is obtained eqref:eq:nhexa_stiffness_matrix.
|
||||
|
||||
\begin{equation}\label{eq:nhexa_stiffness_matrix}
|
||||
\bm{\mathcal{F}} = \underbrace{\bm{J}^T \bm{\mathcal{K}} \bm{J}}_{\bm{K}} \cdot \delta \bm{\mathcal{X}}
|
||||
\bm{\mathcal{F}} = \underbrace{\bm{J}^{\intercal} \bm{\mathcal{K}} \bm{J}}_{\bm{K}} \cdot \delta \bm{\mathcal{X}}
|
||||
\end{equation}
|
||||
where $\bm{K} = \bm{J}^T \bm{\mathcal{K}} \bm{J}$ is identified as the platform stiffness matrix.
|
||||
where $\bm{K} = \bm{J}^{\intercal} \bm{\mathcal{K}} \bm{J}$ is identified as the platform stiffness matrix.
|
||||
|
||||
The inverse relationship is given by the compliance matrix $\bm{C}$:
|
||||
|
||||
\begin{equation}
|
||||
\delta \bm{\mathcal{X}} = \underbrace{(\bm{J}^T \bm{\mathcal{K}} \bm{J})^{-1}}_{\bm{C}} \bm{\mathcal{F}}
|
||||
\delta \bm{\mathcal{X}} = \underbrace{(\bm{J}^{\intercal} \bm{\mathcal{K}} \bm{J})^{-1}}_{\bm{C}} \bm{\mathcal{F}}
|
||||
\end{equation}
|
||||
|
||||
These relationships reveal that the overall platform stiffness and compliance characteristics are determined by two factors:
|
||||
@@ -4367,19 +4429,19 @@ where $\bm{M}$ represents the platform mass matrix, $\bm{\mathcal{X}}$ the platf
|
||||
The primary forces acting on the system are actuator forces $\bm{f}$, elastic forces due to strut stiffness $-\bm{\mathcal{K}} \bm{\mathcal{L}}$ and damping forces in the struts $\bm{\mathcal{C}} \dot{\bm{\mathcal{L}}}$.
|
||||
|
||||
\begin{equation}
|
||||
\Sigma \bm{\mathcal{F}} = \bm{J}^T (\bm{f} - \bm{\mathcal{K}} \bm{\mathcal{L}} - s \bm{\mathcal{C}} \bm{\mathcal{L}}), \quad \bm{\mathcal{K}} = \text{diag}(k_1\,\dots\,k_6),\ \bm{\mathcal{C}} = \text{diag}(c_1\,\dots\,c_6)
|
||||
\Sigma \bm{\mathcal{F}} = \bm{J}^{\intercal} (\bm{f} - \bm{\mathcal{K}} \bm{\mathcal{L}} - s \bm{\mathcal{C}} \bm{\mathcal{L}}), \quad \bm{\mathcal{K}} = \text{diag}(k_1\,\dots\,k_6),\ \bm{\mathcal{C}} = \text{diag}(c_1\,\dots\,c_6)
|
||||
\end{equation}
|
||||
|
||||
Combining these forces and using eqref:eq:nhexa_forward_kinematics_approximate yields the complete dynamic equation eqref:eq:nhexa_dynamical_equations.
|
||||
|
||||
\begin{equation}\label{eq:nhexa_dynamical_equations}
|
||||
\bm{M} s^2 \bm{\mathcal{X}} = \bm{\mathcal{F}} - \bm{J}^T \bm{\mathcal{K}} \bm{J} \bm{\mathcal{X}} - \bm{J}^T \bm{\mathcal{C}} \bm{J} s \bm{\mathcal{X}}
|
||||
\bm{M} s^2 \bm{\mathcal{X}} = \bm{\mathcal{F}} - \bm{J}^{\intercal} \bm{\mathcal{K}} \bm{J} \bm{\mathcal{X}} - \bm{J}^{\intercal} \bm{\mathcal{C}} \bm{J} s \bm{\mathcal{X}}
|
||||
\end{equation}
|
||||
|
||||
The transfer function matrix in the Cartesian frame becomes eqref:eq:nhexa_transfer_function_cart.
|
||||
|
||||
\begin{equation}\label{eq:nhexa_transfer_function_cart}
|
||||
\frac{{\mathcal{X}}}{\bm{\mathcal{F}}}(s) = ( \bm{M} s^2 + \bm{J}^{T} \bm{\mathcal{C}} \bm{J} s + \bm{J}^{T} \bm{\mathcal{K}} \bm{J} )^{-1}
|
||||
\frac{{\mathcal{X}}}{\bm{\mathcal{F}}}(s) = ( \bm{M} s^2 + \bm{J}^{\intercal} \bm{\mathcal{C}} \bm{J} s + \bm{J}^{\intercal} \bm{\mathcal{K}} \bm{J} )^{-1}
|
||||
\end{equation}
|
||||
|
||||
Through coordinate transformation using the Jacobian matrix, the dynamics in the actuator space is obtained eqref:eq:nhexa_transfer_function_struts.
|
||||
@@ -4425,7 +4487,7 @@ Finally, the validated model is employed to analyze the nano-hexapod dynamics, f
|
||||
|
||||
**** Model Definition
|
||||
<<ssec:nhexa_model_def>>
|
||||
***** Geometry
|
||||
****** Geometry
|
||||
|
||||
The Stewart platform's geometry is defined by two principal coordinate frames (Figure ref:fig:nhexa_stewart_model_def): a fixed base frame $\{F\}$ and a moving platform frame $\{M\}$.
|
||||
The joints connecting the actuators to these frames are located at positions ${}^F\bm{a}_i$ and ${}^M\bm{b}_i$ respectively.
|
||||
@@ -4469,14 +4531,14 @@ From these parameters, key kinematic properties can be derived: the strut orient
|
||||
#+end_scriptsize
|
||||
#+end_minipage
|
||||
|
||||
***** Inertia of Plates
|
||||
****** Inertia of Plates
|
||||
|
||||
The fixed base and moving platform were modeled as solid cylindrical bodies.
|
||||
The base platform was characterized by a radius of $120\,mm$ and thickness of $15\,mm$, matching the dimensions of the micro-hexapod's top platform.
|
||||
The moving platform was similarly modeled with a radius of $110\,mm$ and thickness of $15\,mm$.
|
||||
Both platforms were assigned a mass of $5\,kg$.
|
||||
|
||||
***** Joints
|
||||
****** Joints
|
||||
|
||||
The platform's joints play a crucial role in its dynamic behavior.
|
||||
At both the upper and lower connection points, various degrees of freedom can be modeled, including universal joints, spherical joints, and configurations with additional axial and lateral stiffness components.
|
||||
@@ -4485,7 +4547,7 @@ For each degree of freedom, stiffness characteristics can be incorporated into t
|
||||
In the conceptual design phase, a simplified joint configuration is employed: the bottom joints are modeled as two-degree-of-freedom universal joints, while the top joints are represented as three-degree-of-freedom spherical joints.
|
||||
These joints are considered massless and exhibit no stiffness along their degrees of freedom.
|
||||
|
||||
***** Actuators
|
||||
****** Actuators
|
||||
|
||||
The actuator model comprises several key elements (Figure ref:fig:nhexa_actuator_model).
|
||||
At its core, each actuator is modeled as a prismatic joint with internal stiffness $k_a$ and damping $c_a$, driven by a force source $f$.
|
||||
@@ -4585,7 +4647,7 @@ This reduction from six to four observable modes is attributed to the system's s
|
||||
The system's behavior can be characterized in three frequency regions.
|
||||
At low frequencies, well below the first resonance, the plant demonstrates good decoupling between actuators, with the response dominated by the strut stiffness: $\bm{G}(j\omega) \xrightarrow[\omega \to 0]{} \bm{\mathcal{K}}^{-1}$.
|
||||
In the mid-frequency range, the system exhibits coupled dynamics through its resonant modes, reflecting the complex interactions between the platform's degrees of freedom.
|
||||
At high frequencies, above the highest resonance, the response is governed by the payload's inertia mapped to the strut coordinates: $\bm{G}(j\omega) \xrightarrow[\omega \to \infty]{} \bm{J} \bm{M}^{-T} \bm{J}^T \frac{-1}{\omega^2}$
|
||||
At high frequencies, above the highest resonance, the response is governed by the payload's inertia mapped to the strut coordinates: $\bm{G}(j\omega) \xrightarrow[\omega \to \infty]{} \bm{J} \bm{M}^{-T} \bm{J}^{\intercal} \frac{-1}{\omega^2}$
|
||||
|
||||
The force sensor transfer functions, shown in Figure ref:fig:nhexa_multi_body_plant_fm, display characteristics typical of collocated actuator-sensor pairs.
|
||||
Each actuator's transfer function to its associated force sensor exhibits alternating complex conjugate poles and zeros.
|
||||
@@ -4661,7 +4723,7 @@ In the context of the nano-hexapod, two distinct control strategies were examine
|
||||
When controlling a Stewart platform using external metrology that measures the pose of frame $\{B\}$ with respect to $\{A\}$, denoted as $\bm{\mathcal{X}}$, the control architecture can be implemented in either Cartesian or strut space.
|
||||
This choice affects both the control design and the obtained performance.
|
||||
|
||||
***** Control in the Strut space
|
||||
****** Control in the Strut space
|
||||
|
||||
In this approach, as illustrated in Figure ref:fig:nhexa_control_strut, the control is performed in the space of the struts.
|
||||
The Jacobian matrix is used to solve the inverse kinematics in real-time by mapping position errors from Cartesian space $\bm{\epsilon}_{\mathcal{X}}$ to strut space $\bm{\epsilon}_{\mathcal{L}}$.
|
||||
@@ -4672,6 +4734,51 @@ The diagonal terms of the plant (transfer functions from force to displacement o
|
||||
This simplifies the control design because only one controller needs to be tuned.
|
||||
Furthermore, at low frequencies, the plant exhibits good decoupling between the struts, allowing for effective independent control of each axis.
|
||||
|
||||
#+begin_src latex :file nhexa_control_strut.pdf
|
||||
\begin{tikzpicture}
|
||||
% Blocs
|
||||
\node[block={2.0cm}{2.0cm}] (P) {Plant};
|
||||
\coordinate[] (inputF) at ($(P.south west)!0.5!(P.north west)$);
|
||||
\coordinate[] (outputX) at ($(P.south east)!0.5!(P.north east)$);
|
||||
|
||||
\node[block={2.0cm}{2.0cm}, left=0.8 of inputF] (K) {\begin{matrix}K_1 & & 0 \\ & \ddots & \\ 0 & & K_6\end{matrix}};
|
||||
\node[block, left=0.8 of K] (J) {$\bm{J}$};
|
||||
\node[addb={+}{}{}{}{-}, left=0.8 of J] (subr) {};
|
||||
% \node[block, align=center, left=0.6 of subr] (J) {Inverse\\Kinematics};
|
||||
|
||||
% Connections and labels
|
||||
\draw[->] (outputX) -- ++(0.8, 0);
|
||||
\draw[->] ($(outputX) + (0.3, 0)$)node[branch]{} node[above]{$\bm{\mathcal{X}}$} -- ++(0, -1.2) -| (subr.south);
|
||||
\draw[->] (subr.east) -- node[midway, above]{$\bm{\epsilon}_{\mathcal{X}}$} (J.west);
|
||||
\draw[->] (J.east) -- node[midway, above]{$\bm{\epsilon}_{\mathcal{L}}$} (K.west);
|
||||
\draw[->] (K.east) -- node[midway, above]{$\bm{f}$} (inputF);
|
||||
|
||||
\draw[<-] (subr.west)node[above left]{$\bm{r}_{\mathcal{X}}$} -- ++(-0.8, 0);
|
||||
\end{tikzpicture}
|
||||
#+end_src
|
||||
|
||||
#+begin_src latex :file nhexa_control_cartesian.pdf
|
||||
\begin{tikzpicture}
|
||||
% Blocs
|
||||
\node[block={2.0cm}{2.0cm}] (P) {Plant};
|
||||
\coordinate[] (inputF) at ($(P.south west)!0.5!(P.north west)$);
|
||||
\coordinate[] (outputX) at ($(P.south east)!0.5!(P.north east)$);
|
||||
|
||||
\node[block, left=0.8 of inputF] (J) {$\bm{J}^{-T}$};
|
||||
\node[block={2.0cm}{2.0cm}, left=0.8 of J] (K) {\begin{matrix}K_{D_x} & & 0 \\ & \ddots & \\ 0 & & K_{R_z}\end{matrix}};
|
||||
\node[addb={+}{}{}{}{-}, left=0.8 of K] (subr) {};
|
||||
|
||||
% Connections and labels
|
||||
\draw[->] (outputX) -- ++(0.8, 0);
|
||||
\draw[->] ($(outputX) + (0.3, 0)$)node[branch]{} node[above]{$\bm{\mathcal{X}}$} -- ++(0, -1.2) -| (subr.south);
|
||||
|
||||
\draw[->] (subr.east) -- node[midway, above]{$\bm{\epsilon}_{\mathcal{X}}$} (K.west);
|
||||
\draw[->] (K.east) -- node[midway, above]{$\bm{\mathcal{F}}$} (J.west);
|
||||
\draw[->] (J.east) -- node[midway, above]{$\bm{f}$} (inputF.west);
|
||||
\draw[<-] (subr.west)node[above left]{$\bm{r}_{\mathcal{X}}$} -- ++(-0.8, 0);
|
||||
\end{tikzpicture}
|
||||
#+end_src
|
||||
|
||||
#+name: fig:nhexa_control_frame
|
||||
#+caption: Two control strategies
|
||||
#+attr_latex: :options [htbp]
|
||||
@@ -4692,7 +4799,7 @@ Furthermore, at low frequencies, the plant exhibits good decoupling between the
|
||||
#+end_subfigure
|
||||
#+end_figure
|
||||
|
||||
***** Control in Cartesian Space
|
||||
****** Control in Cartesian Space
|
||||
|
||||
Alternatively, control can be implemented directly in Cartesian space, as illustrated in Figure ref:fig:nhexa_control_cartesian.
|
||||
Here, the controller processes Cartesian errors $\bm{\epsilon}_{\mathcal{X}}$ to generate forces and torques $\bm{\mathcal{F}}$, which are then mapped to actuator forces using the transpose of the inverse Jacobian matrix eqref:eq:nhexa_jacobian_forces.
|
||||
@@ -4732,8 +4839,36 @@ The decentralized Integral Force Feedback (IFF) control strategy is implemented
|
||||
|
||||
The corresponding block diagram of the control loop is shown in Figure ref:fig:nhexa_decentralized_iff_schematic, in which the controller $\bm{K}_{\text{IFF}}(s)$ is a diagonal matrix, where each diagonal element is a pure integrator eqref:eq:nhexa_kiff.
|
||||
|
||||
#+begin_src latex :file nhexa_decentralized_iff_schematic.pdf
|
||||
\begin{tikzpicture}
|
||||
% Blocs
|
||||
\node[block={2.0cm}{2.0cm}] (P) {Plant};
|
||||
\coordinate[] (input) at ($(P.south west)!0.5!(P.north west)$);
|
||||
\coordinate[] (outputH) at ($(P.south east)!0.2!(P.north east)$);
|
||||
\coordinate[] (outputL) at ($(P.south east)!0.8!(P.north east)$);
|
||||
|
||||
\node[block, above=0.2 of P] (Klac) {$\bm{K}_\text{IFF}$};
|
||||
\node[addb, left=0.8 of input] (addF) {};
|
||||
|
||||
% Connections and labels
|
||||
\draw[->] (outputL) -- ++(0.7, 0) coordinate(eastlac) |- (Klac.east);
|
||||
\node[above right] at (outputL){$\bm{f}_n$};
|
||||
\draw[->] (Klac.west) -| (addF.north);
|
||||
\draw[->] (addF.east) -- (input) node[above left]{$\bm{f}$};
|
||||
|
||||
\draw[->] (outputH) -- ++(1.7, 0) node[above left]{$\bm{\mathcal{L}}$};
|
||||
\draw[<-] (addF.west) -- ++(-0.8, 0) node[above right]{$\bm{f}^{\prime}$};
|
||||
|
||||
\begin{scope}[on background layer]
|
||||
\node[fit={(Klac.north-|eastlac) (addF.west|-P.south)}, fill=black!20!white, draw, dashed, inner sep=8pt] (Pi) {};
|
||||
\node[anchor={north west}] at (Pi.north west){\footnotesize{Damped Plant}};
|
||||
\end{scope}
|
||||
\end{tikzpicture}
|
||||
#+end_src
|
||||
|
||||
#+name: fig:nhexa_decentralized_iff_schematic
|
||||
#+caption: Schematic of the implemented decentralized IFF controller. The damped plant has a new inputs $\bm{f}^{\prime}$
|
||||
#+RESULTS:
|
||||
[[file:figs/nhexa_decentralized_iff_schematic.png]]
|
||||
|
||||
\begin{equation}\label{eq:nhexa_kiff}
|
||||
@@ -4783,8 +4918,47 @@ Following the analysis from Section ref:ssec:nhexa_control_space, the control is
|
||||
The Jacobian matrix $\bm{J}^{-1}$ performs (approximate) real-time approximate inverse kinematics to map position errors from Cartesian space $\bm{\epsilon}_{\mathcal{X}}$ to strut space $\bm{\epsilon}_{\mathcal{L}}$.
|
||||
A diagonal High Authority Controller $\bm{K}_{\text{HAC}}$ then processes these errors in the frame of the struts.
|
||||
|
||||
#+begin_src latex :file nhexa_hac_iff_schematic.pdf
|
||||
\begin{tikzpicture}
|
||||
% Blocs
|
||||
\node[block={2.0cm}{2.0cm}] (P) {Plant};
|
||||
\coordinate[] (input) at ($(P.south west)!0.5!(P.north west)$);
|
||||
\coordinate[] (outputH) at ($(P.south east)!0.2!(P.north east)$);
|
||||
\coordinate[] (outputL) at ($(P.south east)!0.8!(P.north east)$);
|
||||
|
||||
\node[block, above=0.2 of P] (Klac) {$\bm{K}_\text{IFF}$};
|
||||
\node[addb, left=0.8 of input] (addF) {};
|
||||
|
||||
\node[block, left=0.8 of addF] (Khac) {$\bm{K}_\text{HAC}$};
|
||||
\node[block, left=0.8 of Khac] (inverseK) {$\bm{J}$};
|
||||
|
||||
\node[addb={+}{}{}{}{-}, left=0.8 of inverseK] (subL) {};
|
||||
|
||||
% Connections and labels
|
||||
\draw[->] (outputL) -- ++(0.7, 0) coordinate(eastlac) |- (Klac.east);
|
||||
\node[above right] at (outputL){$\bm{f}_n$};
|
||||
\draw[->] (Klac.west) -| (addF.north);
|
||||
\draw[->] (addF.east) -- (input) node[above left]{$\bm{f}$};
|
||||
|
||||
\draw[->] (outputH) -- ++(1.7, 0) node[above left]{$\bm{\mathcal{X}}$};
|
||||
\draw[->] (Khac.east) node[above right]{$\bm{f}^{\prime}$} -- (addF.west);
|
||||
|
||||
\draw[->] ($(outputH) + (1.2, 0)$)node[branch]{} |- ($(subL.south)+(0, -1.2)$) -- (subL.south);
|
||||
\draw[->] (subL.east) -- (inverseK.west) node[above left]{$\bm{\epsilon}_\mathcal{X}$};
|
||||
\draw[->] (inverseK.east) -- (Khac.west) node[above left]{$\bm{\epsilon}_\mathcal{L}$};
|
||||
|
||||
\draw[<-] (subL.west) -- ++(-0.8, 0) node[above right]{$\bm{r}_\mathcal{X}$};
|
||||
|
||||
\begin{scope}[on background layer]
|
||||
\node[fit={(Klac.north-|eastlac) (addF.west|-P.south)}, fill=black!20!white, draw, dashed, inner sep=8pt] (Pi) {};
|
||||
\node[anchor={north west}] at (Pi.north west){\footnotesize{Damped Plant}};
|
||||
\end{scope}
|
||||
\end{tikzpicture}
|
||||
#+end_src
|
||||
|
||||
#+name: fig:nhexa_hac_iff_schematic
|
||||
#+caption: HAC-IFF control architecture with the High Authority Controller being implemented in the frame of the struts
|
||||
#+RESULTS:
|
||||
[[file:figs/nhexa_hac_iff_schematic.png]]
|
||||
|
||||
The effect of decentralized IFF on the plant dynamics can be observed by comparing two sets of transfer functions.
|
||||
@@ -4879,7 +5053,6 @@ This approach combines decentralized Integral Force Feedback for active damping
|
||||
|
||||
This study establishes the theoretical framework necessary for the subsequent development and validation of the NASS.
|
||||
|
||||
|
||||
** Validation of the Concept
|
||||
<<sec:nass>>
|
||||
*** Introduction
|
||||
@@ -5586,12 +5759,12 @@ The analysis is significantly simplified when considering small motions, as the
|
||||
|
||||
\begin{equation}\label{eq:detail_kinematics_jacobian}
|
||||
\begin{bmatrix} \delta l_1 \\ \delta l_2 \\ \delta l_3 \\ \delta l_4 \\ \delta l_5 \\ \delta l_6 \end{bmatrix} = \underbrace{\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
|
||||
{{}^A\hat{\bm{s}}_1}^{\intercal} & ({}^A\bm{b}_1 \times {}^A\hat{\bm{s}}_1)^{\intercal} \\
|
||||
{{}^A\hat{\bm{s}}_2}^{\intercal} & ({}^A\bm{b}_2 \times {}^A\hat{\bm{s}}_2)^{\intercal} \\
|
||||
{{}^A\hat{\bm{s}}_3}^{\intercal} & ({}^A\bm{b}_3 \times {}^A\hat{\bm{s}}_3)^{\intercal} \\
|
||||
{{}^A\hat{\bm{s}}_4}^{\intercal} & ({}^A\bm{b}_4 \times {}^A\hat{\bm{s}}_4)^{\intercal} \\
|
||||
{{}^A\hat{\bm{s}}_5}^{\intercal} & ({}^A\bm{b}_5 \times {}^A\hat{\bm{s}}_5)^{\intercal} \\
|
||||
{{}^A\hat{\bm{s}}_6}^{\intercal} & ({}^A\bm{b}_6 \times {}^A\hat{\bm{s}}_6)^{\intercal}
|
||||
\end{bmatrix}}_{\bm{J}} \begin{bmatrix} \delta x \\ \delta y \\ \delta z \\ \delta \theta_x \\ \delta \theta_y \\ \delta \theta_z \end{bmatrix}
|
||||
\end{equation}
|
||||
|
||||
@@ -5709,28 +5882,28 @@ The contribution of joints stiffness is not considered here, as the joints were
|
||||
However, theoretical frameworks for evaluating flexible joint contribution to the stiffness matrix have been established in the literature [[cite:&mcinroy00_desig_contr_flexur_joint_hexap;&mcinroy02_model_desig_flexur_joint_stewar]].
|
||||
|
||||
\begin{equation}\label{eq:detail_kinematics_stiffness_matrix}
|
||||
\bm{K} = \bm{J}^T \bm{\mathcal{K}} \bm{J}
|
||||
\bm{K} = \bm{J}^{\intercal} \bm{\mathcal{K}} \bm{J}
|
||||
\end{equation}
|
||||
|
||||
It is assumed that the stiffness of all struts is the same: $\bm{\mathcal{K}} = k \cdot \mathbf{I}_6$.
|
||||
In that case, the obtained stiffness matrix linearly depends on the strut stiffness $k$, and is structured as shown in equation eqref:eq:detail_kinematics_stiffness_matrix_simplified.
|
||||
|
||||
\begin{equation}\label{eq:detail_kinematics_stiffness_matrix_simplified}
|
||||
\bm{K} = k \bm{J}^T \bm{J} =
|
||||
\bm{K} = k \bm{J}^{\intercal} \bm{J} =
|
||||
k \left[
|
||||
\begin{array}{c|c}
|
||||
\Sigma_{i = 0}^{6} \hat{\bm{s}}_i \cdot \hat{\bm{s}}_i^T & \Sigma_{i = 0}^{6} \bm{\hat{s}}_i \cdot ({}^A\bm{b}_i \times {}^A\hat{\bm{s}}_i)^T \\
|
||||
\Sigma_{i = 0}^{6} \hat{\bm{s}}_i \cdot \hat{\bm{s}}_i^{\intercal} & \Sigma_{i = 0}^{6} \bm{\hat{s}}_i \cdot ({}^A\bm{b}_i \times {}^A\hat{\bm{s}}_i)^{\intercal} \\
|
||||
\hline
|
||||
\Sigma_{i = 0}^{6} ({}^A\bm{b}_i \times {}^A\hat{\bm{s}}_i) \cdot \hat{\bm{s}}_i^T & \Sigma_{i = 0}^{6} ({}^A\bm{b}_i \times {}^A\hat{\bm{s}}_i) \cdot ({}^A\bm{b}_i \times {}^A\hat{\bm{s}}_i)^T\\
|
||||
\Sigma_{i = 0}^{6} ({}^A\bm{b}_i \times {}^A\hat{\bm{s}}_i) \cdot \hat{\bm{s}}_i^{\intercal} & \Sigma_{i = 0}^{6} ({}^A\bm{b}_i \times {}^A\hat{\bm{s}}_i) \cdot ({}^A\bm{b}_i \times {}^A\hat{\bm{s}}_i)^{\intercal}\\
|
||||
\end{array}
|
||||
\right]
|
||||
\end{equation}
|
||||
|
||||
****** Translation Stiffness
|
||||
|
||||
As shown by equation eqref:eq:detail_kinematics_stiffness_matrix_simplified, the translation stiffnesses (the $3 \times 3$ top left terms of the stiffness matrix) only depend on the orientation of the struts and not their location: $\hat{\bm{s}}_i \cdot \hat{\bm{s}}_i^T$.
|
||||
As shown by equation eqref:eq:detail_kinematics_stiffness_matrix_simplified, the translation stiffnesses (the $3 \times 3$ top left terms of the stiffness matrix) only depend on the orientation of the struts and not their location: $\hat{\bm{s}}_i \cdot \hat{\bm{s}}_i^{\intercal}$.
|
||||
In the extreme case where all struts are vertical ($s_i = [0\ 0\ 1]$), a vertical stiffness of $6k$ is achieved, but with null stiffness in the horizontal directions.
|
||||
If two struts are aligned with the X axis, two struts with the Y axis, and two struts with the Z axis, then $\hat{\bm{s}}_i \cdot \hat{\bm{s}}_i^T = 2 \bm{I}_3$, resulting in well-distributed stiffness along all directions.
|
||||
If two struts are aligned with the X axis, two struts with the Y axis, and two struts with the Z axis, then $\hat{\bm{s}}_i \cdot \hat{\bm{s}}_i^{\intercal} = 2 \bm{I}_3$, resulting in well-distributed stiffness along all directions.
|
||||
This configuration corresponds to the cubic architecture presented in Section ref:sec:detail_kinematics_cubic.
|
||||
|
||||
When the struts are oriented more vertically, as shown in Figure ref:fig:detail_kinematics_stewart_mobility_vert_struts, the vertical stiffness increases while the horizontal stiffness decreases.
|
||||
@@ -5761,7 +5934,7 @@ Under very specific conditions, the equations of motion in the Cartesian frame,
|
||||
These conditions are studied in Section ref:ssec:detail_kinematics_cubic_dynamic.
|
||||
|
||||
\begin{equation}\label{eq:detail_kinematics_transfer_function_cart}
|
||||
\frac{{\mathcal{X}}}{\bm{\mathcal{F}}}(s) = ( \bm{M} s^2 + \bm{J}^{T} \bm{\mathcal{C}} \bm{J} s + \bm{J}^{T} \bm{\mathcal{K}} \bm{J} )^{-1}
|
||||
\frac{{\mathcal{X}}}{\bm{\mathcal{F}}}(s) = ( \bm{M} s^2 + \bm{J}^{\intercal} \bm{\mathcal{C}} \bm{J} s + \bm{J}^{\intercal} \bm{\mathcal{K}} \bm{J} )^{-1}
|
||||
\end{equation}
|
||||
|
||||
In the frame of the struts, the equations of motion eqref:eq:detail_kinematics_transfer_function_struts are well decoupled at low frequency.
|
||||
@@ -5850,6 +6023,152 @@ The unit vectors corresponding to the edges of the cube are described by equatio
|
||||
\hat{\bm{s}}_6 = \begin{bmatrix} \frac{-1}{\sqrt{6}} \\ \frac{ 1}{\sqrt{2}} \\ \frac{1}{\sqrt{3}} \end{bmatrix}
|
||||
\end{equation}
|
||||
|
||||
#+begin_src latex :file detail_kinematics_cubic_schematic_full.pdf :results file
|
||||
\begin{tikzpicture}
|
||||
\begin{scope}[rotate={45}, shift={(0, 0, -4)}]
|
||||
% We first define the coordinate of the points of the Cube
|
||||
\coordinate[] (bot) at (0,0,4);
|
||||
\coordinate[] (top) at (4,4,0);
|
||||
\coordinate[] (A1) at (0,0,0);
|
||||
\coordinate[] (A2) at (4,0,4);
|
||||
\coordinate[] (A3) at (0,4,4);
|
||||
\coordinate[] (B1) at (4,0,0);
|
||||
\coordinate[] (B2) at (4,4,4);
|
||||
\coordinate[] (B3) at (0,4,0);
|
||||
|
||||
% Center of the Cube
|
||||
\coordinate[] (cubecenter) at ($0.5*(bot) + 0.5*(top)$);
|
||||
|
||||
% We draw parts of the cube that corresponds to the Stewart platform
|
||||
\draw[] (A1)node[]{$\bullet$} -- (B1)node[]{$\bullet$} -- (A2)node[]{$\bullet$} -- (B2)node[]{$\bullet$} -- (A3)node[]{$\bullet$} -- (B3)node[]{$\bullet$} -- (A1);
|
||||
|
||||
% ai and bi are computed
|
||||
\def\lfrom{0.0}
|
||||
\def\lto{1.0}
|
||||
|
||||
\coordinate(a1) at ($(A1) - \lfrom*(A1) + \lfrom*(B1)$);
|
||||
\coordinate(b1) at ($(A1) - \lto*(A1) + \lto*(B1)$);
|
||||
\coordinate(a2) at ($(A2) - \lfrom*(A2) + \lfrom*(B1)$);
|
||||
\coordinate(b2) at ($(A2) - \lto*(A2) + \lto*(B1)$);
|
||||
\coordinate(a3) at ($(A2) - \lfrom*(A2) + \lfrom*(B2)$);
|
||||
\coordinate(b3) at ($(A2) - \lto*(A2) + \lto*(B2)$);
|
||||
\coordinate(a4) at ($(A3) - \lfrom*(A3) + \lfrom*(B2)$);
|
||||
\coordinate(b4) at ($(A3) - \lto*(A3) + \lto*(B2)$);
|
||||
\coordinate(a5) at ($(A3) - \lfrom*(A3) + \lfrom*(B3)$);
|
||||
\coordinate(b5) at ($(A3) - \lto*(A3) + \lto*(B3)$);
|
||||
\coordinate(a6) at ($(A1) - \lfrom*(A1) + \lfrom*(B3)$);
|
||||
\coordinate(b6) at ($(A1) - \lto*(A1) + \lto*(B3)$);
|
||||
|
||||
% We draw the fixed and mobiles platforms
|
||||
\path[fill=colorblue, opacity=0.2] (a1) -- (a2) -- (a3) -- (a4) -- (a5) -- (a6) -- cycle;
|
||||
\path[fill=colorblue, opacity=0.2] (b1) -- (b2) -- (b3) -- (b4) -- (b5) -- (b6) -- cycle;
|
||||
\draw[color=colorblue, dashed] (a1) -- (a2) -- (a3) -- (a4) -- (a5) -- (a6) -- cycle;
|
||||
\draw[color=colorblue, dashed] (b1) -- (b2) -- (b3) -- (b4) -- (b5) -- (b6) -- cycle;
|
||||
|
||||
% The legs of the hexapod are drawn
|
||||
\draw[color=colorblue] (a1)node{$\bullet$} -- (b1)node{$\bullet$};
|
||||
\draw[color=colorblue] (a2)node{$\bullet$} -- (b2)node{$\bullet$};
|
||||
\draw[color=colorblue] (a3)node{$\bullet$} -- (b3)node{$\bullet$};
|
||||
\draw[color=colorblue] (a4)node{$\bullet$} -- (b4)node{$\bullet$};
|
||||
\draw[color=colorblue] (a5)node{$\bullet$} -- (b5)node{$\bullet$};
|
||||
\draw[color=colorblue] (a6)node{$\bullet$} -- (b6)node{$\bullet$};
|
||||
|
||||
% Unit vector
|
||||
\draw[color=colorred, ->] ($0.9*(a1)+0.1*(b1)$)node{$\bullet$} -- ($0.65*(a1)+0.35*(b1)$)node[right]{$\hat{\bm{s}}_3$};
|
||||
\draw[color=colorred, ->] ($0.9*(a2)+0.1*(b2)$)node{$\bullet$} -- ($0.65*(a2)+0.35*(b2)$)node[left]{$\hat{\bm{s}}_4$};
|
||||
\draw[color=colorred, ->] ($0.9*(a3)+0.1*(b3)$)node{$\bullet$} -- ($0.65*(a3)+0.35*(b3)$)node[below]{$\hat{\bm{s}}_5$};
|
||||
\draw[color=colorred, ->] ($0.9*(a4)+0.1*(b4)$)node{$\bullet$} -- ($0.65*(a4)+0.35*(b4)$)node[below]{$\hat{\bm{s}}_6$};
|
||||
\draw[color=colorred, ->] ($0.9*(a5)+0.1*(b5)$)node{$\bullet$} -- ($0.65*(a5)+0.35*(b5)$)node[left]{$\hat{\bm{s}}_1$};
|
||||
\draw[color=colorred, ->] ($0.9*(a6)+0.1*(b6)$)node{$\bullet$} -- ($0.65*(a6)+0.35*(b6)$)node[right]{$\hat{\bm{s}}_2$};
|
||||
|
||||
% Labels
|
||||
\node[above=0.1 of B1] {$\tilde{\bm{b}}_3 = \tilde{\bm{b}}_4$};
|
||||
\node[above=0.1 of B2] {$\tilde{\bm{b}}_5 = \tilde{\bm{b}}_6$};
|
||||
\node[above=0.1 of B3] {$\tilde{\bm{b}}_1 = \tilde{\bm{b}}_2$};
|
||||
\end{scope}
|
||||
|
||||
% Height of the Hexapod
|
||||
\coordinate[] (sizepos) at ($(a2)+(0.2, 0)$);
|
||||
\coordinate[] (origin) at (0,0,0);
|
||||
|
||||
\draw[->, color=colorgreen] (cubecenter.center) node[above right]{$\{B\}$} -- ++(0,0,1);
|
||||
\draw[->, color=colorgreen] (cubecenter.center) -- ++(1,0,0);
|
||||
\draw[->, color=colorgreen] (cubecenter.center) -- ++(0,1,0);
|
||||
|
||||
\node[] at (cubecenter.center){$\bullet$};
|
||||
\node[above left] at (cubecenter.center){$\{C\}$};
|
||||
|
||||
% Useful part of the cube
|
||||
\draw[<->, dashed] ($(A2)+(0.5,0)$) -- node[midway, right]{$H_{C}$} ($(B1)+(0.5,0)$);
|
||||
\end{tikzpicture}
|
||||
#+end_src
|
||||
|
||||
#+begin_src latex :file detail_kinematics_cubic_schematic.pdf :results file
|
||||
\begin{tikzpicture}
|
||||
\begin{scope}[rotate={45}, shift={(0, 0, -4)}]
|
||||
% We first define the coordinate of the points of the Cube
|
||||
\coordinate[] (bot) at (0,0,4);
|
||||
\coordinate[] (top) at (4,4,0);
|
||||
\coordinate[] (A1) at (0,0,0);
|
||||
\coordinate[] (A2) at (4,0,4);
|
||||
\coordinate[] (A3) at (0,4,4);
|
||||
\coordinate[] (B1) at (4,0,0);
|
||||
\coordinate[] (B2) at (4,4,4);
|
||||
\coordinate[] (B3) at (0,4,0);
|
||||
|
||||
% Center of the Cube
|
||||
\coordinate[] (cubecenter) at ($0.5*(bot) + 0.5*(top)$);
|
||||
|
||||
% We draw parts of the cube that corresponds to the Stewart platform
|
||||
\draw[] (A1)node[]{$\bullet$} -- (B1)node[]{$\bullet$} -- (A2)node[]{$\bullet$} -- (B2)node[]{$\bullet$} -- (A3)node[]{$\bullet$} -- (B3)node[]{$\bullet$} -- (A1);
|
||||
|
||||
% ai and bi are computed
|
||||
\def\lfrom{0.2}
|
||||
\def\lto{0.8}
|
||||
|
||||
\coordinate(a1) at ($(A1) - \lfrom*(A1) + \lfrom*(B1)$);
|
||||
\coordinate(b1) at ($(A1) - \lto*(A1) + \lto*(B1)$);
|
||||
\coordinate(a2) at ($(A2) - \lfrom*(A2) + \lfrom*(B1)$);
|
||||
\coordinate(b2) at ($(A2) - \lto*(A2) + \lto*(B1)$);
|
||||
\coordinate(a3) at ($(A2) - \lfrom*(A2) + \lfrom*(B2)$);
|
||||
\coordinate(b3) at ($(A2) - \lto*(A2) + \lto*(B2)$);
|
||||
\coordinate(a4) at ($(A3) - \lfrom*(A3) + \lfrom*(B2)$);
|
||||
\coordinate(b4) at ($(A3) - \lto*(A3) + \lto*(B2)$);
|
||||
\coordinate(a5) at ($(A3) - \lfrom*(A3) + \lfrom*(B3)$);
|
||||
\coordinate(b5) at ($(A3) - \lto*(A3) + \lto*(B3)$);
|
||||
\coordinate(a6) at ($(A1) - \lfrom*(A1) + \lfrom*(B3)$);
|
||||
\coordinate(b6) at ($(A1) - \lto*(A1) + \lto*(B3)$);
|
||||
|
||||
% We draw the fixed and mobiles platforms
|
||||
\path[fill=colorblue, opacity=0.2] (a1) -- (a2) -- (a3) -- (a4) -- (a5) -- (a6) -- cycle;
|
||||
\path[fill=colorblue, opacity=0.2] (b1) -- (b2) -- (b3) -- (b4) -- (b5) -- (b6) -- cycle;
|
||||
\draw[color=colorblue, dashed] (a1) -- (a2) -- (a3) -- (a4) -- (a5) -- (a6) -- cycle;
|
||||
\draw[color=colorblue, dashed] (b1) -- (b2) -- (b3) -- (b4) -- (b5) -- (b6) -- cycle;
|
||||
|
||||
% The legs of the hexapod are drawn
|
||||
\draw[color=colorblue] (a1)node{$\bullet$} -- (b1)node{$\bullet$}node[below right]{$\bm{b}_3$};
|
||||
\draw[color=colorblue] (a2)node{$\bullet$} -- (b2)node{$\bullet$}node[right]{$\bm{b}_4$};
|
||||
\draw[color=colorblue] (a3)node{$\bullet$} -- (b3)node{$\bullet$}node[above right]{$\bm{b}_5$};
|
||||
\draw[color=colorblue] (a4)node{$\bullet$} -- (b4)node{$\bullet$}node[above left]{$\bm{b}_6$};
|
||||
\draw[color=colorblue] (a5)node{$\bullet$} -- (b5)node{$\bullet$}node[left]{$\bm{b}_1$};
|
||||
\draw[color=colorblue] (a6)node{$\bullet$} -- (b6)node{$\bullet$}node[below left]{$\bm{b}_2$};
|
||||
\end{scope}
|
||||
|
||||
% Height of the Hexapod
|
||||
\coordinate[] (sizepos) at ($(a2)+(0.2, 0)$);
|
||||
\coordinate[] (origin) at (0,0,0);
|
||||
|
||||
\draw[->, color=colorgreen] ($(cubecenter.center)+(0,2.0,0)$) node[above right]{$\{B\}$} -- ++(0,0,1);
|
||||
\draw[->, color=colorgreen] ($(cubecenter.center)+(0,2.0,0)$) -- ++(1,0,0);
|
||||
\draw[->, color=colorgreen] ($(cubecenter.center)+(0,2.0,0)$) -- ++(0,1,0);
|
||||
|
||||
\node[] at (cubecenter.center){$\bullet$};
|
||||
\node[right] at (cubecenter.center){$\{C\}$};
|
||||
|
||||
\draw[<->, dashed] (cubecenter.center) -- node[midway, right]{$H$} ($(cubecenter.center)+(0,2.0,0)$);
|
||||
\end{tikzpicture}
|
||||
#+end_src
|
||||
|
||||
#+name: fig:detail_kinematics_cubic_schematic_cases
|
||||
#+caption: Cubic architecture. Struts are represented in blue. The cube's center by a black dot. The Struts can match the cube's edges (\subref{fig:detail_kinematics_cubic_schematic_full}) or just take a portion of the edge (\subref{fig:detail_kinematics_cubic_schematic})
|
||||
#+attr_latex: :options [htbp]
|
||||
@@ -5964,8 +6283,29 @@ Furthermore, an inverse relationship exists between the cube's dimension and rot
|
||||
This section examines the dynamics of the cubic architecture in the Cartesian frame which corresponds to the transfer function from forces and torques $\bm{\mathcal{F}}$ to translations and rotations $\bm{\mathcal{X}}$ of the top platform.
|
||||
When relative motion sensors are integrated in each strut (measuring $\bm{\mathcal{L}}$), the pose $\bm{\mathcal{X}}$ is computed using the Jacobian matrix as shown in Figure ref:fig:detail_kinematics_centralized_control.
|
||||
|
||||
#+begin_src latex :file detail_kinematics_centralized_control.pdf
|
||||
\begin{tikzpicture}
|
||||
\node[block] (Jt) at (0, 0) {$\bm{J}^{-T}$};
|
||||
\node[block, right= of Jt] (G) {$\bm{G}$};
|
||||
\node[block, right= of G] (J) {$\bm{J}^{-1}$};
|
||||
\node[block, left= of Jt] (Kx) {$\bm{K}_{\mathcal{X}}$};
|
||||
|
||||
\draw[->] (Kx.east) -- node[midway, above]{$\bm{\mathcal{F}}$} (Jt.west);
|
||||
\draw[->] (Jt.east) -- (G.west) node[above left]{$\bm{\tau}$};
|
||||
\draw[->] (G.east) -- (J.west) node[above left]{$\bm{\mathcal{L}}$};
|
||||
\draw[->] (J.east) -- ++(1.0, 0);
|
||||
\draw[->] ($(J.east) + (0.5, 0)$)node[]{$\bullet$} node[above]{$\bm{\mathcal{X}}$} -- ++(0, -1) -| ($(Kx.west) + (-0.5, 0)$) -- (Kx.west);
|
||||
|
||||
\begin{scope}[on background layer]
|
||||
\node[fit={(Jt.south west) (J.north east)}, fill=black!20!white, draw, dashed, inner sep=4pt] (Px) {};
|
||||
\node[anchor={south}] at (Px.north){\small{Cartesian Plant}};
|
||||
\end{scope}
|
||||
\end{tikzpicture}
|
||||
#+end_src
|
||||
|
||||
#+name: fig:detail_kinematics_centralized_control
|
||||
#+caption: Typical control architecture in the cartesian frame
|
||||
#+RESULTS:
|
||||
[[file:figs/detail_kinematics_centralized_control.png]]
|
||||
|
||||
****** Low frequency and High frequency coupling
|
||||
@@ -6058,8 +6398,26 @@ The orthogonal arrangement of struts in the cubic architecture suggests a potent
|
||||
Two sensor types integrated in the struts are considered: displacement sensors and force sensors.
|
||||
The control architecture is illustrated in Figure ref:fig:detail_kinematics_decentralized_control, where $\bm{K}_{\mathcal{L}}$ represents a diagonal transfer function matrix.
|
||||
|
||||
#+begin_src latex :file detail_kinematics_decentralized_control.pdf
|
||||
\begin{tikzpicture}
|
||||
\node[block] (G) at (0,0) {$\bm{G}$};
|
||||
|
||||
\node[block, left= of G] (Kl) {$\bm{K}_{\mathcal{L}}$};
|
||||
|
||||
\draw[->] (Kl.east) -- node[midway, above]{$\bm{\tau}$} (G.west);
|
||||
\draw[->] (G.east) -- ++(1.0, 0);
|
||||
\draw[->] ($(G.east) + (0.5, 0)$)node[]{$\bullet$} node[above]{$\bm{\mathcal{L}}$} -- ++(0, -1) -| ($(Kl.west) + (-0.5, 0)$) -- (Kl.west);
|
||||
|
||||
\begin{scope}[on background layer]
|
||||
\node[fit={(G.south west) (G.north east)}, fill=black!20!white, draw, dashed, inner sep=4pt] (Pl) {};
|
||||
\node[anchor={south}] at (Pl.north){\small{Strut Plant}};
|
||||
\end{scope}
|
||||
\end{tikzpicture}
|
||||
#+end_src
|
||||
|
||||
#+name: fig:detail_kinematics_decentralized_control
|
||||
#+caption: Decentralized control in the frame of the struts.
|
||||
#+RESULTS:
|
||||
[[file:figs/detail_kinematics_decentralized_control.png]]
|
||||
|
||||
The obtained plant dynamics in the frame of the struts are compared for two Stewart platforms.
|
||||
@@ -6377,7 +6735,7 @@ This specification will guide the design of the flexible joints.
|
||||
*** Conclusion
|
||||
<<sec:detail_kinematics_conclusion>>
|
||||
|
||||
This section has explored the optimization of the nano-hexapod geometry for the Nano Active Stabilization System (NASS).
|
||||
This chapter has explored the optimization of the nano-hexapod geometry for the Nano Active Stabilization System (NASS).
|
||||
|
||||
First, a review of existing Stewart platforms revealed two main geometric categories: cubic architectures, characterized by mutually orthogonal struts arranged along the edges of a cube, and non-cubic architectures with varied strut orientations.
|
||||
While cubic architectures are prevalent in the literature and attributed with beneficial properties such as simplified kinematics, uniform stiffness, and reduced cross-coupling, the performed analysis revealed that some of these advantages should be more nuanced or context-dependent than commonly described.
|
||||
@@ -10728,7 +11086,7 @@ The control strategy here is to apply a diagonal control in the frame of the str
|
||||
To conduct this interaction analysis, the acrfull:rga $\bm{\Lambda_G}$ is first computed using eqref:eq:test_id31_rga for the plant dynamics identified with the multiple payload masses.
|
||||
|
||||
\begin{equation}\label{eq:test_id31_rga}
|
||||
\bm{\Lambda_G}(\omega) = \bm{G}(j\omega) \star \left(\bm{G}(j\omega)^{-1}\right)^{T}, \quad (\star \text{ means element wise multiplication})
|
||||
\bm{\Lambda_G}(\omega) = \bm{G}(j\omega) \star \left(\bm{G}(j\omega)^{-1}\right)^{\intercal}, \quad (\star \text{ means element wise multiplication})
|
||||
\end{equation}
|
||||
|
||||
Then, acrshort:rga numbers are computed using eqref:eq:test_id31_rga_number and are use as a metric for interaction [[cite:&skogestad07_multiv_feedb_contr chapt. 3.4]].
|
||||
@@ -11310,7 +11668,8 @@ Moreover, the systematic approach to system development and validation, along wi
|
||||
:PROPERTIES:
|
||||
:UNNUMBERED: notoc
|
||||
:END:
|
||||
<<sec:concept_conclusion>>
|
||||
<<sec:test_conclusion>>
|
||||
|
||||
* Conclusion and Future Work
|
||||
<<chap:conclusion>>
|
||||
|
||||
@@ -11363,8 +11722,7 @@ Moreover, the systematic approach to system development and validation, along wi
|
||||
[fn:modal_2]Kistler 9722A2000. Sensitivity of $2.3\,mV/N$ and measurement range of $2\,kN$
|
||||
[fn:modal_1]PCB 356B18. Sensitivity is $1\,V/g$, measurement range is $\pm 5\,g$ and bandwidth is $0.5$ to $5\,\text{kHz}$.
|
||||
|
||||
[fn:ustation_12]It was probably caused by rust of the linear guides along its stroke.
|
||||
[fn:ustation_11]A 3-Axis L4C geophone manufactured Sercel was used.
|
||||
[fn:ustation_11]It was probably caused by rust of the linear guides along its stroke.
|
||||
[fn:ustation_10]Laser source is manufactured by Agilent (5519b).
|
||||
[fn:ustation_9]The special optics (straightness interferometer and reflector) are manufactured by Agilent (10774A).
|
||||
[fn:ustation_8]C8 capacitive sensors and CPL290 capacitive driver electronics from Lion Precision.
|
||||
|
Reference in New Issue
Block a user