Write second section about Stewart platforms

This commit is contained in:
Thomas Dehaeze 2025-02-10 14:24:50 +01:00
parent f56939f127
commit a7f85ba00b
5 changed files with 438 additions and 379 deletions

Binary file not shown.

Binary file not shown.

After

Width:  |  Height:  |  Size: 75 KiB

View File

@ -212,7 +212,7 @@ CLOSED: [2025-02-05 Wed 16:04]
- simulations => validation of the concept
** TODO [#A] Make sure the Simulink file for the Stewart platform is working well
SCHEDULED: <2025-02-08 Sat>
SCHEDULED: <2025-02-10 Mon>
It should be the exact model reference that will be included in the NASS model (referenced subsystem).
@ -254,6 +254,7 @@ Better understand this: https://en.wikipedia.org/wiki/Virtual_work
Also add link or explanation for this equation.
** TODO [#C] Mention the Toolbox (maybe make a DOI for that)
** DONE [#B] Define the geometry for the simplified nano-hexapod
CLOSED: [2025-02-06 Thu 18:56]
@ -395,22 +396,25 @@ To control such system, it requires several tools to study interaction (Section
<<sec:nhexa_stewart_platform>>
** Introduction :ignore:
# Most of this section is based on [[file:~/Cloud/work-projects/ID31-NASS/matlab/stewart-simscape/org/kinematic-study.org][kinematic-study.org]]
The Stewart platform, first introduced by Stewart in 1965 [[cite:&stewart65_platf_with_six_degrees_freed]] for flight simulation applications, represents a significant milestone in parallel manipulator design.
This mechanical architecture has evolved far beyond its original purpose, finding applications across diverse fields from precision positioning systems to robotic surgery.
The fundamental design consists of two platforms connected by six adjustable struts in parallel, creating a fully parallel manipulator capable of six degrees of freedom motion.
- Some history about Stewart platforms
- What is so special and why it is so used in different fields: give examples
Explain advantages compared to serial architecture
- Little review (very quick: two extreme sizes, piezo + voice coil)
Complete review of Stewart platforms will be made in Chapter 2
- Presentation of tools used to analyze the properties of the Stewart platform => useful for design and control
Unlike serial manipulators where errors worsen through the kinematic chain, parallel architectures distribute loads across multiple actuators, leading to enhanced mechanical stiffness and improved positioning accuracy.
This parallel configuration also results in superior dynamic performance, as the actuators directly contribute to the platform's motion without intermediate linkages.
These characteristics of Stewart platforms have made them particularly valuable in applications requiring high precision and stiffness.
For the NASS application, the Stewart platform architecture presents three key advantages.
First, as a fully parallel manipulator, all motion errors of the micro-station can be compensated through the coordinated action of the six actuators.
Second, its compact design compared to serial manipulators makes it ideal for integration on top micro-station where only $95\,mm$ of height is available.
Third, the good dynamical properties should enable high bandwidth positioning control.
The Stewart Platform is very adapted for the NASS application for the following reasons:
- it is a fully parallel manipulator, thus all the motions errors can be compensated
- it is very compact compared to a serial manipulator
- it has high stiffness and good dynamic performances
While Stewart platforms excel in precision and stiffness, they typically exhibit a relatively limited workspace compared to serial manipulators.
However, this limitation is not significant for the NASS application, as the required motion range corresponds to the positioning errors of the micro-station which are in the order of $10\,\mu m$.
The main disadvantage of Stewart platforms is the small workspace when compare the serial manipulators which is not a problem here.
This section provides a comprehensive analysis of the Stewart platform's properties, focusing on aspects crucial for precision positioning applications.
The analysis encompasses the platform's kinematic relationships (Section ref:ssec:nhexa_stewart_platform_kinematics), the use of the Jacobian matrix (Section ref:ssec:nhexa_stewart_platform_jacobian), static behavior (Section ref:ssec:nhexa_stewart_platform_static), and dynamic characteristics (Section ref:ssec:nhexa_stewart_platform_dynamics).
These theoretical foundations form the basis for subsequent design decisions and control strategies, which will be elaborated in later sections.
** Matlab Init :noexport:ignore:
#+begin_src matlab :tangle no :exports none :results silent :noweb yes :var current_dir=(file-name-directory buffer-file-name)
@ -440,34 +444,27 @@ The main disadvantage of Stewart platforms is the small workspace when compare t
** Mechanical Architecture
<<ssec:nhexa_stewart_platform_architecture>>
A Stewart manipulator consists of two platforms connected by six struts (Figure ref:fig:nhexa_stewart_architecture).
Each strut is connected to the fixed and the mobile platforms with a joint.
Typically, a universal joint is used on one side while a spherical joint is used on the other side[fn:1].
In the strut, there is an active element working as a prismatic joint.
The Stewart platform consists of two rigid platforms connected by six struts arranged in parallel (Figure ref:fig:nhexa_stewart_architecture).
Each strut incorporates an active prismatic joint that enables controlled length variation, with its ends attached to the fixed and mobile platforms through joints.
The typical configuration consists of a universal joint at one end and a spherical joint at the other, providing the necessary degrees of freedom[fn:1].
#+name: fig:nhexa_stewart_architecture
#+caption: Schematical representation of the Stewart platform architecture.
[[file:figs/nhexa_stewart_architecture.png]]
Such architecture allows to move the mobile platform with respect to the fixed platform in 6 degrees-of-freedom.
It is therefore a /fully/ parallel manipulator as the number of actuators is equal to the number of DoF.
It is also a symmetrical parallel manipulator as typically all the struts are identical.
To facilitate rigorous analysis of the Stewart platform, four reference frames are defined:
- The fixed base frame $\{F\}$, located at the center of the base platform's bottom surface, serves as the mounting reference for the support structure.
- The mobile frame $\{M\}$, situated at the center of the top platform's upper surface, provides a reference for payload mounting.
- The point-of-interest frame $\{A\}$, fixed to the base but positioned at the workspace center.
- The moving point-of-interest frame $\{B\}$, attached to the mobile platform and coincident with frame $\{A\}$ in the home position.
In order to study the Stewart platform, four important frames are typically defined:
- $\{F\}$: Frame fixed on the base and located at the center of its bottom surface.
This is used to fix the Stewart platform to some support.
- $\{M\}$: Frame fixed to the moving platform and located at the center of its top surface.
This is used to place things on top of the Stewart platform.
- $\{A\}$: Frame fixed to the fixed base, but located at the point-of-interest.
- $\{B\}$: Frame fixed to the moving platform and located at the same point-of-interest than $\{A\}$.
Frames $\{F\}$ and $\{M\}$ serve primarily to define the joint locations.
On the other hand, frames $\{A\}$ and $\{B\}$ are used to describe the relative motion of the two platforms through the position vector ${}^A\bm{P}_B$ of frame $\{B\}$ expressed in frame $\{A\}$ and the rotation matrix ${}^A\bm{R}_B$ expressing the orientation of $\{B\}$ with respect to $\{A\}$.
For the nano-hexapod, frames $\{A\}$ and $\{B\}$ are chosen to be located at the theoretical focus point of the X-ray light which is $150\,mm$ above the top platform, i.e. above $\{M\}$.
Frames $\{F\}$ and $\{M\}$ are useful to describe the location of the joints in a meaningful frame.
On the other hand, frames $\{A\}$ and $\{B\}$ are used to describe the relative motion of the two platforms through the position vector ${}^A\bm{P}_B$ of $\{B\}$ expressed in $\{A\}$ and the rotation matrix ${}^A\bm{R}_B$ expressing the orientation of $\{B\}$ with respect to $\{A\}$.
For the nano-hexapod, these frames are chosen to be located at the theoretical focus point of the X-ray light ($150\,mm$ above the top platform, i.e. above $\{M\}$).
Location of the joints and orientation and length of the struts are very important for the study of the Stewart platform as well.
The center of rotation for the joint fixed to the base is noted $\bm{a}_i$, while $b_i$ is used for the top joints.
The struts orientation are indicated by the unit vectors $\hat{\bm{s}}_i$ and their lengths by the scalars $l_i$.
Location of the joints and orientation and length of the struts are crucial for subsequent kinematic, static, and dynamic analyses of the Stewart platform.
The center of rotation for the joint fixed to the base is noted $\bm{a}_i$, while $b_i$ is used for the top platform joints.
The struts orientation are represented by the unit vectors $\hat{\bm{s}}_i$ and their lengths by the scalars $l_i$.
This is summarized in Figure ref:fig:nhexa_stewart_notations.
#+name: fig:nhexa_stewart_notations
@ -478,31 +475,29 @@ This is summarized in Figure ref:fig:nhexa_stewart_notations.
<<ssec:nhexa_stewart_platform_kinematics>>
**** Introduction :ignore:
Kinematic analysis refers to the study of the geometry of motion of a robot, without considering the forces that cause the motion.
The kinematic analysis of the Stewart platform involves understanding the geometric relationships between the platform position/orientation and the actuator lengths, without considering the forces involved.
**** Loop Closure
At the displacement level, the /closure/ of each kinematic loop (illustrated in Figure ref:fig:nhexa_stewart_loop_closure) can be express in the vector form as
\begin{equation}
\vec{ab} = \vec{aa_i} + \vec{a_ib_i} - \vec{bb_i} \quad \text{for } i = 1 \text{ to } 6
\end{equation}
in which $\vec{aa_i}$ and $\vec{bb_i}$ can be easily obtained from the location of the joint on the base and on the moving platform.
The foundation of the kinematic analysis lies in the geometric constraints imposed by each strut, which can be expressed through 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.
The loop closure can be written as the unknown pose variables ${}^A\bm{P}$ and ${}^A\bm{R}_B$, the position vectors describing the known geometry of the base and of the moving platform, $\bm{a}_i$ and $\bm{b}_i$, and the strut vector $l_i {}^A\hat{\bm{s}}_i$:
\begin{equation}\label{eq:nhexa_loop_close}
{}^A\bm{P} = {}^A\bm{a}_i + l_i{}^A\hat{\bm{s}}_i - {}^A\bm{R}_B {}^B\bm{b}_i \quad \text{for } i=1 \text{ to } 6
\begin{equation}\label{eq:nhexa_loop_closure}
{}^A\bm{P}_B = {}^A\bm{a}_i + l_i{}^A\hat{\bm{s}}_i - \underbrace{{}^B\bm{b}_i}_{{}^A\bm{R}_B {}^B\bm{b}_i} \quad \text{for } i=1 \text{ to } 6
\end{equation}
Such equation links the pose variables ${}^A\bm{P}$ and ${}^A\bm{R}_B$, the position vectors describing the known geometry of the base and of the moving platform, $\bm{a}_i$ and $\bm{b}_i$, and the strut vector $l_i {}^A\hat{\bm{s}}_i$:
#+name: fig:nhexa_stewart_loop_closure
#+caption: Notations to compute the kinematic loop closure
[[file:figs/nhexa_stewart_loop_closure.png]]
**** Inverse Kinematics
For /inverse kinematic analysis/, it is assumed that the position ${}^A\bm{P}$ and orientation of the moving platform ${}^A\bm{R}_B$ are given and the problem is to obtain the joint variables $\bm{\mathcal{L}} = \left[ l_1, l_2, l_3, l_4, l_5, l_6 \right]$.
This problem can be easily solved using the loop closures eqref:eq:nhexa_loop_close.
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$).
This problem can be solved analytically using the loop closure equations eqref:eq:nhexa_loop_closure.
The obtain strut lengths are given by eqref:eq:nhexa_inverse_kinematics.
The obtain joint variables are:
\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}
\end{equation}
@ -512,49 +507,29 @@ Otherwise, the solution gives complex numbers.
**** Forward Kinematics
In /forward kinematic analysis/, it is assumed that the vector of strut lengths $\bm{\mathcal{L}}$ is given and the problem is to find the position ${}^A\bm{P}$ and the orientation ${}^A\bm{R}_B$.
This is a difficult problem that requires to solve nonlinear equations.
In a next section, an approximate solution of the forward kinematics problem is proposed for small displacements.
The forward kinematic problem seeks to determine the platform pose $\bm{\mathcal{X}}$ given a set of strut lengths $\bm{\mathcal{L}}$.
Unlike the inverse kinematics, this presents a significant challenge as it requires solving a system of nonlinear equations.
While various numerical methods exist for solving this problem, they can be computationally intensive and may not guarantee convergence to the correct solution.
For the nano-hexapod application, where displacements are typically small, an approximate solution based on linearization around the operating point provides a practical alternative.
This approximation, developed in subsequent sections through the Jacobian matrix analysis, proves particularly useful for real-time control applications.
# TODO - Add references
** The Jacobian Matrix
<<ssec:nhexa_stewart_platform_jacobian>>
**** Introduction :ignore:
In vector calculus, the Jacobian matrix represents the best linear approximation of a vector-valued function near a working point.
Consider a function $\bm{f}: \mathbb{R}^n \rightarrow \mathbb{R}^m$ with continuous first-order partial derivatives.
For any input $\bm{x} \in \mathbb{R}^n$, this function produces an output $\bm{f}(\bm{x}) \in \mathbb{R}^m$.
The Jacobian matrix $\bm{J}$ of $\bm{f}$ at point $\bm{x}$ is the $m \times n$ matrix whose $(i,j)$ entry is:
$J_{ij} = \frac{\partial f_i}{\partial x_j}$
This matrix represents the linear transformation that best approximates $\bm{f}$ in a neighborhood of $\bm{x}$.
In other words, for points sufficiently close to $\bm{x}$, the function $\bm{f}$ behaves approximately like its Jacobian matrix.
The Jacobian matrix plays a central role in analyzing the Stewart platform's behavior, providing a linear mapping between 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 - Velocity Loop Closure
Let's note:
- $\bm{\mathcal{L}} = \left[ l_1, l_2, \ldots, l_6 \right]^T$: vector of actuated joint coordinates
- $\bm{\mathcal{X}} = \left[ {}^A\bm{P}, \bm{}^A\hat{\bm{s}} \right]^T$: vector of platform motion variables
As was shown 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.
$\bm{\mathcal{L}}$ and $\bm{\mathcal{X}}$ are related through a system of /nonlinear algebraic equations/ representing the /kinematic constraints imposed by the struts/, which can be generally written as $f(\bm{\mathcal{L}}, \bm{\mathcal{X}}) = 0$.
By taking the time derivative of the position loop close eqref:eq:nhexa_loop_closure, the /velocity loop closure/ is obtained eqref:eq:nhexa_loop_closure_velocity.
We can differentiate this equation with respect to time and obtain:
\begin{equation*}
\bm{J}_x \dot{\bm{\mathcal{X}}} = \bm{J}_l \dot{\bm{\mathcal{L}}} \quad \text{where} \quad
\bm{J}_x = \frac{\partial f}{\partial \bm{\mathcal{X}}} \quad \text{and} \quad \bm{J}_l = -\frac{\partial f}{\partial \bm{\mathcal{L}}}
\end{equation*}
With:
- $\dot{\bm{\mathcal{L}}} = [ \dot{l}_1, \dot{l}_2, \dot{l}_3, \dot{l}_4, \dot{l}_5, \dot{l}_6 ]^T$
- $\dot{\bm{X}} = [^A\bm{v}_p, {}^A\bm{\omega}]^T$:
The *general Jacobian matrix* is defined as:
\begin{equation*}
\dot{\bm{\mathcal{L}}} = \bm{J} \dot{\bm{\mathcal{X}}} \quad \text{with} \quad \bm{J} = {\bm{J}_l}^{-1} \bm{J}_x
\end{equation*}
The *velocity loop closures* are used for *obtaining the Jacobian matrices* in a straightforward manner:
\[{}^A\bm{P} + {}^A\bm{R}_B {}^B\bm{b}_i = l_i {}^A\hat{\bm{s}}_i + {}^A\bm{a}_i\]
By taking the time derivative of the position loop close eqref:eq:nhexa_loop_close, the velocity loop closure is obtained:
\begin{equation}
\begin{equation}\label{eq:nhexa_loop_closure_velocity}
{}^A\bm{v}_p + {}^A \dot{\bm{R}}_B {}^B\bm{b}_i + {}^A\bm{R}_B \underbrace{{}^B\dot{\bm{b}_i}}_{=0} = \dot{l}_i {}^A\hat{\bm{s}}_i + l_i {}^A\dot{\hat{\bm{s}}}_i + \underbrace{{}^A\dot{a}_i}_{=0}
\end{equation}
@ -562,19 +537,21 @@ Moreover, we have:
- ${}^A\dot{\bm{R}}_B {}^B\bm{b}_i = {}^A\bm{\omega} \times {}^A\bm{R}_B {}^B\bm{b}_i = {}^A\bm{\omega} \times {}^A\bm{b}_i$ in which ${}^A\bm{\omega}$ denotes the angular velocity of the moving platform expressed in the fixed frame $\{\bm{A}\}$.
- $l_i {}^A\dot{\hat{\bm{s}}}_i = l_i \left( {}^A\bm{\omega}_i \times \hat{\bm{s}}_i \right)$ in which ${}^A\bm{\omega}_i$ is the angular velocity of strut $i$ express in fixed frame $\{\bm{A}\}$.
By multiplying both sides by ${}^A\hat{s}_i$:
By multiplying both sides by ${}^A\hat{s}_i$, eqref:eq:nhexa_loop_closure_velocity_bis is obtained.
\begin{equation}
\begin{equation}\label{eq:nhexa_loop_closure_velocity_bis}
{}^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}
Finally:
\begin{equation}
\hat{\bm{s}}_i {}^A\bm{v}_p + ({}^A\bm{b}_i \times \hat{\bm{s}}_i) {}^A\bm{\omega} = \dot{l}_i
Equation eqref:eq:nhexa_loop_closure_velocity_bis can be rearranged in a 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.
\begin{equation}\label{eq:nhexa_jacobian_velocities}
\boxed{\dot{\bm{\mathcal{L}}} = \bm{J} \dot{\bm{\mathcal{X}}}}
\end{equation}
We can rearrange the equations in a matrix form:
\[ \dot{\bm{\mathcal{L}}} = \bm{J} \dot{\bm{\mathcal{X}}} \quad \text{with} \ \dot{\bm{\mathcal{L}}} = [ \dot{l}_1 \ \dots \ \dot{l}_6 ]^T \ \text{and} \ \dot{\bm{\mathcal{X}}} = [{}^A\bm{v}_p ,\ {}^A\bm{\omega}]^T \]
The matrix $\bm{J}$ is called the Jacobian matrix, and is defined by eqref:eq:nhexa_jacobian, with:
- $\hat{\bm{s}}_i$ the orientation of the struts expressed in $\{A\}$
- $\bm{b}_i$ the position of the joints with respect to $O_B$ and express in $\{A\}$
\begin{equation}\label{eq:nhexa_jacobian}
\bm{J} = \begin{bmatrix}
@ -587,21 +564,17 @@ We can rearrange the equations in a matrix form:
\end{bmatrix}
\end{equation}
$\bm{J}$ then depends only on:
- $\hat{\bm{s}}_i$ the orientation of the struts expressed in $\{A\}$
- $\bm{b}_i$ the position of the joints with respect to $O_B$ and express in $\{A\}$
The Jacobian matrix links the rate of change of strut length to the velocity and angular velocity of the top platform with respect to the fixed base.
This Jacobian matrix needs to be recomputed for every Stewart platform pose.
This Jacobian matrix $\bm{J}$ therefore links the rate of change of 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 as it depends on the actual pose of of the manipulator.
**** Approximate solution of the Forward and Inverse Kinematic problems
For small displacements mobile platform displacement $\delta \bm{\mathcal{X}} = [\delta x, \delta y, \delta z, \delta \theta_x, \delta \theta_y, \delta \theta_z ]^T$ around $\bm{\mathcal{X}}_0$, the associated joint displacement can be computed using the Jacobian (approximate solution of the inverse kinematic problem):
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 (approximate solution of the inverse kinematic problem):
\begin{equation}\label{eq:nhexa_inverse_kinematics_approximate}
\boxed{\delta\bm{\mathcal{L}} = \bm{J} \delta\bm{\mathcal{X}}}
\end{equation}
Similarly, for small joint displacements $\delta\bm{\mathcal{L}} = [ \delta l_1,\ \dots,\ \delta l_6 ]^T$ around $\bm{\mathcal{L}}_0$, it is possible to find the induced small displacement of the mobile platform (approximate solution of the forward kinematic problem):
Similarly, for small joint displacements $\delta\bm{\mathcal{L}}$, it is possible to find the induced small displacement of the mobile platform (approximate solution of the forward kinematic problem):
\begin{equation}\label{eq:nhexa_forward_kinematics_approximate}
\boxed{\delta\bm{\mathcal{X}} = \bm{J}^{-1} \delta\bm{\mathcal{L}}}
\end{equation}
@ -611,182 +584,197 @@ As the inverse kinematic can be easily solved exactly this is not much useful, h
**** Range validity of the approximate inverse kinematics
As we know how to exactly solve the Inverse kinematic problem, we can compare the exact solution with the approximate solution using the Jacobian matrix.
For small displacements, the approximate solution is expected to work well.
We would like here to determine up to what displacement this approximation can be considered as correct.
The accuracy of the Jacobian-based forward kinematics solution was estimated through a systematic error analysis.
For a series of platform positions along the $x$-axis, the exact strut lengths are computed using the analytical inverse kinematics equation eqref:eq:nhexa_inverse_kinematics.
These strut lengths are then used with the Jacobian to estimate the platform pose, from which the error between the estimated and true poses can be calculated.
Then, we can determine the range for which the approximate inverse kinematic is valid.
This will also gives us the range for which the approximate forward kinematic is valid.
The estimation errors in the $x$, $y$, and $z$ directions are shown in Figure ref:fig:nhexa_forward_kinematics_approximate_errors.
The results demonstrate that for displacements up to approximately $1\,\%$ of the hexapod's size (which corresponds to $100\,\mu m$ as the size of the Stewart platform is here $\approx 100\,mm$), the Jacobian approximation provides excellent accuracy.
- [ ] [[file:~/Cloud/work-projects/ID31-NASS/matlab/stewart-simscape/org/kinematic-study.org::*Estimation of the range validity of the approximate inverse kinematics][Estimation of the range validity of the approximate inverse kinematics]]
This finding has particular significance for the Nano-hexapod application.
Since the maximum required stroke ($\approx 100\,\mu m$) is three orders of magnitude smaller than the stewart platform size ($\approx 100\,mm$), the Jacobian matrix can be considered constant throughout the workspace.
It can be computed once at the rest position and used for both forward and inverse kinematics with high accuracy.
Let's first compare the perfect and approximate solution of the inverse for pure $x$ translations.
#+begin_src matlab
%% Estimate the errors associated with approximate forward kinematics using the Jacobian matrix
stewart = initializeSimplifiedNanoHexapod('H', 100e-3, 'MO_B', 0);
The approximate and exact required strut stroke to have the wanted mobile platform $x$ displacement are computed.
The estimated error is shown in Figure etc...
Xrs = logspace(-6, -1, 100); % Wanted X translation of the mobile platform [m]
% Compute the strut exact length for each X-position
Ls_exact = zeros(6, length(Xrs));
for i = 1:length(Xrs)
[~, L_exact(:, i)] = inverseKinematics(stewart, 'AP', [Xrs(i); 0; 0]);
end
For small wanted displacements (up to $\approx 1\%$ of the size of the Hexapod), the approximate inverse kinematic solution using the Jacobian matrix is quite correct.
% From the strut length, compute the stewart pose using the Jacobian matrix
Xrs_approx = zeros(6, length(Xrs));
for i = 1:length(Xrs)
Xrs_approx(:, i) = inv(stewart.geometry.J)*L_exact(:, i);
end
#+end_src
In the case of the Nano-hexapod, the maximum stroke is estimate to the around $100\,\mu m$ while its size is around $100\,mm$, therefore the fixed Jacobian matrix is a very good approximate for the forward and inverse kinematics.
#+begin_src matlab :exports none :results none
%% Errors associated with the use of the Jacobian matrix to solve the forward kinematic problem
figure;
hold on;
plot(1e6*Xrs, 1e9*abs(Xrs - Xrs_approx(1, :)), 'DisplayName', '$\epsilon_x$');
plot(1e6*Xrs, 1e9*abs(Xrs_approx(2, :)), 'DisplayName', '$\epsilon_y$');
plot(1e6*Xrs, 1e9*abs(Xrs_approx(3, :)), 'DisplayName', '$\epsilon_z$');
plot(1e6*Xrs, 1e6*Xrs, 'k--', 'DisplayName', '$0.1\%$ error');
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
leg = legend('location', 'northwest', 'FontSize', 8, 'NumColumns', 1);
leg.ItemTokenSize(1) = 15;
xlim([1, 1e4]); ylim([1, 1e4]);
xticks([1, 10, 100, 1000, 10000]);
yticks([1, 10, 100, 1000, 10000]);
xticklabels({'$1\mu m$', '$10\mu m$', '$100\mu m$', '$1mm$', '$10mm$'});
yticklabels({'$1nm$', '$10nm$', '$100nm$', '$1\mu m$', '$10\mu m$'});
#+end_src
#+begin_src matlab :tangle no :exports results :results file replace
exportFig('figs/nhexa_forward_kinematics_approximate_errors.pdf', 'width', 'wide', 'height', 'normal');
#+end_src
#+name: fig:nhexa_forward_kinematics_approximate_errors
#+caption: Errors associated with the use of the Jacobian matrix to solve the forward kinematic problem
#+RESULTS:
[[file:figs/nhexa_forward_kinematics_approximate_errors.png]]
**** Static Forces
Let's note $\bm{\tau} = [\tau_1, \tau_2, \cdots, \tau_6]^T$ the vector of actuator forces applied in each strut and $\bm{\mathcal{F}} = [\bm{f}, \bm{n}]^T$ external force/torque action on the mobile platform at $\bm{O}_B$.
The static force analysis of the Stewart platform can be elegantly 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.
The /principle of virtual work/ states that the total virtual work $\delta W$, done by all actuators and external forces is equal to zero:
Let $\bm{\tau} = [\tau_1, \tau_2, \cdots, \tau_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$.
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{\tau}^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 principle of virtual work can thus be expressed as:
\begin{equation}
\delta W = \bm{\tau}^T \delta \bm{\mathcal{L}} - \bm{\mathcal{F}}^T \delta \bm{\mathcal{X}} = 0
\delta W = \bm{\tau}^T \delta \bm{\mathcal{L}} - \bm{\mathcal{F}}^T \delta \bm{\mathcal{X}} = 0
\end{equation}
From the definition of the Jacobian ($\delta \bm{\mathcal{L}} = \bm{J} \cdot \delta \bm{\mathcal{X}}$), we have $\left( \bm{\tau}^T \bm{J} - \bm{\mathcal{F}}^T \right) \delta \bm{\mathcal{X}} = 0$ that holds for any $\delta \bm{\mathcal{X}}$, hence:
Using the Jacobian relationship that links virtual displacements eqref:eq:nhexa_inverse_kinematics_approximate, this equation becomes:
\begin{equation}
\left( \bm{\tau}^T \bm{J} - \bm{\mathcal{F}}^T \right) \delta \bm{\mathcal{X}} = 0
\end{equation}
Since this equation must hold for any virtual displacement $\delta \bm{\mathcal{X}}$, the following force mapping relationships can be derived:
\begin{equation}\label{eq:nhexa_jacobian_forces}
\bm{\tau}^T \bm{J} - \bm{\mathcal{F}}^T = 0 \quad \Rightarrow \quad \boxed{\bm{\mathcal{F}} = \bm{J}^T \bm{\tau}} \quad \text{and} \quad \boxed{\bm{\tau} = \bm{J}^{-T} \bm{\mathcal{F}}}
\end{equation}
Therefore, the same Jacobian matrix can also be used to map actuator forces to forces and torques applied on the mobile platform at the defined frame $\{B\}$.
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.
** Static Analysis
** TODO Static Analysis
<<ssec:nhexa_stewart_platform_static>>
How stiffness varies with orientation of struts.
Same with stroke?
Or maybe in the detailed chapter?
The static stiffness characteristics of the Stewart platform play a crucial role in its performance, particularly for precision positioning applications.
These characteristics are fundamentally determined by both the actuator properties and the platform geometry.
The stiffness of the actuator $k_i$ links the applied actuator force $\delta \tau_i$ and the corresponding small deflection $\delta l_i$:
\begin{equation*}
\tau_i = k_i \delta l_i, \quad i = 1,\ \dots,\ 6
\end{equation*}
If we combine these 6 relations:
\begin{equation*}
\bm{\tau} = \mathcal{K} \delta \bm{\mathcal{L}} \quad \mathcal{K} = \text{diag}\left[ k_1,\ \dots,\ k_6 \right]
\end{equation*}
Substituting $\bm{\tau} = \bm{J}^{-T} \bm{\mathcal{F}}$ and $\delta \bm{\mathcal{L}} = \bm{J} \cdot \delta \bm{\mathcal{X}}$ gives
Starting from the individual actuators, the relationship between applied force $\delta \tau_i$ and resulting displacement $\delta l_i$ for each strut $i$ is characterized by its stiffness $k_i$:
\begin{equation}
\bm{\mathcal{F}} = \bm{J}^T \mathcal{K} \bm{J} \cdot \delta \bm{\mathcal{X}}
\end{equation}
And then we identify the stiffness matrix $\bm{K}$:
\begin{equation}
\bm{K} = \bm{J}^T \mathcal{K} \bm{J}
\tau_i = k_i \delta l_i, \quad i = 1,\ \dots,\ 6
\end{equation}
If the stiffness matrix $\bm{K}$ is inversible, the *compliance matrix* of the manipulator is defined as
These individual relationships can be combined into a matrix form using the diagonal stiffness matrix $\mathcal{K}$:
\begin{equation}
\bm{C} = \bm{K}^{-1} = (\bm{J}^T \mathcal{K} \bm{J})^{-1}
\bm{\tau} = \mathcal{K} \delta \bm{\mathcal{L}}, \quad \mathcal{K} = \text{diag}\left[ k_1,\ \dots,\ k_6 \right]
\end{equation}
The compliance matrix of a manipulator shows the mapping of the moving platform wrench applied at $\bm{O}_B$ to its small deflection by
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 \mathcal{K} \bm{J}}_{\bm{K}} \delta \bm{\mathcal{X}}
\end{equation}
where $\bm{K} = \bm{J}^T \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}} = \bm{C} \cdot \bm{\mathcal{F}}
\delta \bm{\mathcal{X}} = \underbrace{(\bm{J}^T \mathcal{K} \bm{J})^{-1}}_{\bm{C}} \bm{\mathcal{F}}
\end{equation}
Conclusion: stiffness/compliance of the Stewart platform depends on the Jacobian matrix, therefore on the position and orientation of the struts.
These relationships reveal that the overall platform stiffness and compliance characteristics are determined by two factors:
- The individual actuator stiffnesses represented by $\mathcal{K}$
- The geometric configuration embodied in the Jacobian matrix $\bm{J}$
This geometric dependency means that the platform's stiffness varies throughout its workspace, as the Jacobian matrix changes with the platform's position and orientation.
For the NASS application, where the workspace is relatively small compared to the platform dimensions, these variations can be considered minimal.
However, the initial geometric configuration significantly impacts the overall stiffness characteristics.
The relationship between maximum stroke and stiffness presents another important design consideration.
As both parameters are influenced by the geometric configuration, their optimization involves inherent trade-offs that must be carefully balanced based on application requirements.
The optimization of this configuration to achieve desired stiffness properties while having enough stroke will be addressed during the detailed design phase.
** Dynamic Analysis
<<ssec:nhexa_stewart_platform_dynamics>>
If one wants to study the dynamics of the Stewart platform, ...
Let's suppose that the struts are mass-less, that the joints are perfect.
Suppose the
Very complex => multi-body model
For instance, compute the plant for massless struts and perfect joints (will be compared with Simscape model).
But say that if we want to model more complex cases, it becomes impractical (cite papers).
The dynamic behavior of a Stewart platform can be analyzed through various approaches, depending on the desired level of model fidelity.
For initial analysis, we consider a simplified model with the following assumptions:
- Massless struts
- Ideal joints without friction or compliance
- Rigid platform and base
Under these assumptions, the system dynamics can be expressed in the Cartesian space as:
\begin{equation}
M s^2 \mathcal{X} = \Sigma \mathcal{F}
\end{equation}
Forces are:
- Actuator forces: $\mathcal{F} = \bm{J}^T \tau$
- Stiffness of the struts: $-J^T \mathcal{K} J \mathcal{X}$
- Damping of the struts: $-J^T \mathcal{C} J \dot{\mathcal{X}}$
where $M$ represents the platform mass matrix, $\mathcal{X}$ the platform pose, and $\Sigma \mathcal{F}$ the sum of forces acting on the platform.
The primary forces acting on the system are actuator forces $\bm{\tau}$, elastic forces due to strut stiffness $-\mathcal{K} \mathcal{L}$ and damping forces in the struts $\mathcal{C} \dot{\mathcal{L}}$.
\begin{equation}
\Sigma \bm{\mathcal{F}} = \bm{J}^T (\tau - \mathcal{K} \mathcal{L} - s \mathcal{C} \mathcal{L}), \quad \mathcal{K} = \text{diag}(k_1\,\dots\,k_6),\ \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}
M s^2 \mathcal{X} = \mathcal{F} - J^T \mathcal{K} J \mathcal{X} - J^T \mathcal{C} J s \mathcal{X}
\end{equation}
Equation in the cartesian frame:
\begin{equation}
\frac{\mathcal{X}}{\mathcal{F}}(s) = ( M s^2 + \bm{J}^{T} \mathcal{C} J s + \bm{J}^{T} \mathcal{K} J )^{-1}
The transfer function in the Cartesian frame becomes eqref:eq:nhexa_transfer_function_cart.
\begin{equation}\label{eq:nhexa_transfer_function_cart}
\frac{\mathcal{X}}{\mathcal{F}}(s) = ( M s^2 + \bm{J}^{T} \mathcal{C} J s + \bm{J}^{T} \mathcal{K} J )^{-1}
\end{equation}
Using the Jacobian, equation in the strut frame:
\begin{equation}
Through coordinate transformation using the Jacobian matrix, the dynamics in the actuator space is obtained eqref:eq:nhexa_transfer_function_struts.
\begin{equation}\label{eq:nhexa_transfer_function_struts}
\frac{\mathcal{L}}{\tau}(s) = ( \bm{J}^{-T} M \bm{J}^{-1} s^2 + \mathcal{C} + \mathcal{K} )^{-1}
\end{equation}
It becomes much more complex when:
- model the mass of the struts, or more complex strut dynamics
- take into account flexible joint stiffnesses
- would not be practical to combine with the dynamical equations of the micro-station
While this simplified model provides useful insights, real Stewart platforms exhibit more complex behaviors.
Several factors significantly increase model complexity:
- Strut dynamics, including mass distribution and internal resonances
- Joint compliance and friction effects
- Supporting structure dynamics and payload dynamics, which are both very critical for NASS
#+begin_src matlab
%% Plant using Analytical Equations
% Stewart platform definition
k = 1e6; % Actuator stiffness [N/m]
c = 1e1; % Actuator damping [N/(m/s)]
# TODO - Add citations [[cite:&mcinroy00_desig_contr_flexur_joint_hexap;&mcinroy02_model_desig_flexur_joint_stewar]]
stewart = initializeSimplifiedNanoHexapod('Mpm', 1e-3, 'actuator_type', '1dof', 'actuator_k', k, 'actuator_c', c);
% Payload: Cylinder
h = 300e-3; % Height of the cylinder [m]
r = 110e-3; % Radius of the cylinder [m]
m = 10; % Mass of the payload [kg]
initializeSample('type', 'cylindrical', 'm', m, 'H', h, 'R', r);
% Mass Matrix
M = zeros(6,6);
M(1,1) = m;
M(2,2) = m;
M(3,3) = m;
M(4,4) = 1/12*m*(3*r^2 + h^2);
M(5,5) = 1/12*m*(3*r^2 + h^2);
M(6,6) = 1/2*m*r^2;
% Stiffness and Damping matrices
K = k*eye(6);
C = c*eye(6);
% Compute plant in the frame of the struts
G_analytical = inv(ss(inv(stewart.geometry.J')*M*inv(stewart.geometry.J)*s^2 + C*s + K));
% Compare with Simscape model
initializeLoggingConfiguration('log', 'none');
initializeController('type', 'open-loop');
% Input/Output definition
clear io; io_i = 1;
io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Inputs [N]
io(io_i) = linio([mdl, '/plant'], 2, 'openoutput', [], 'dL'); io_i = io_i + 1; % Encoders [m]
G_simscape = linearize(mdl, io);
G_simscape.InputName = {'f1', 'f2', 'f3', 'f4', 'f5', 'f6'};
G_simscape.OutputName = {'dL1', 'dL2', 'dL3', 'dL4', 'dL5', 'dL6'};
#+end_src
#+begin_src matlab
bodeFig({G_analytical(1,1), G_simscape(1,1), G_analytical(1,2), G_simscape(1,2)})
#+end_src
These additional effects make analytical modeling impractical for complete system analysis.
** Conclusion
:PROPERTIES:
:UNNUMBERED: t
:END:
Dynamic analysis of parallel manipulators presents an *inherent complexity due to their closed-loop structure and kinematic constraints*.
The fundamental characteristics of the Stewart platform have been analyzed in this chapter.
Essential kinematic relationships were developed through loop closure equations, from which both exact and approximate solutions for the inverse and forward kinematic problems were derived.
The Jacobian matrix was established as a central mathematical tool, through which crucial insights into velocity relationships, static force transmission, and dynamic behavior of the platform were obtained.
All depends on the geometry.
Reasonable choice of geometry is made in chapter 1.
Optimization of the geometry will be made in chapter 2.
For the NASS application, where displacements are typically limited to the micrometer range, the accuracy of linearized models using a constant Jacobian matrix has been demonstrated, by which both analysis and control can be significantly simplified.
However, additional complexities such as strut masses, joint compliance, and supporting structure dynamics must be considered in the full dynamic behavior.
This will be performed in the next section using a multi-body model.
The static analysis supposed that joints are perfect.
It gets more complex if flexible joints are used with stiffnesses that are not negligible.
[[cite:&mcinroy00_desig_contr_flexur_joint_hexap;&mcinroy02_model_desig_flexur_joint_stewar]]
All these characteristics (maneuverability, stiffness, dynamics, etc.) are fundamentally determined by the platform's geometry.
While a reasonable geometric configuration will be used to validate the NASS during this conceptual phase, the optimization of these geometric parameters will be explored during the detailed design phase.
* Multi-Body Model
:PROPERTIES:
@ -802,8 +790,6 @@ It gets more complex if flexible joints are used with stiffnesses that are not n
Cite papers that tries to model the stewart platform analytically
Advantage: it will be easily included in the model of the NASS
- Mention the Toolbox (maybe make a DOI for that)
- [ ] Have a table somewhere that summarizes the main characteristics of the nano-hexapod model
- location of joints
- size / mass of platforms, etc...
@ -873,6 +859,54 @@ Definition of each part + Plant with defined inputs/outputs (force sensor, relat
- Compare with analytical formulas (see number of states)
- Effect of 2DoF APA on IFF plant?
#+begin_src matlab
%% Plant using Analytical Equations
% Stewart platform definition
k = 1e6; % Actuator stiffness [N/m]
c = 1e1; % Actuator damping [N/(m/s)]
stewart = initializeSimplifiedNanoHexapod('Mpm', 1e-3, 'actuator_type', '1dof', 'actuator_k', k, 'actuator_c', c);
% Payload: Cylinder
h = 300e-3; % Height of the cylinder [m]
r = 110e-3; % Radius of the cylinder [m]
m = 10; % Mass of the payload [kg]
initializeSample('type', 'cylindrical', 'm', m, 'H', h, 'R', r);
% Mass Matrix
M = zeros(6,6);
M(1,1) = m;
M(2,2) = m;
M(3,3) = m;
M(4,4) = 1/12*m*(3*r^2 + h^2);
M(5,5) = 1/12*m*(3*r^2 + h^2);
M(6,6) = 1/2*m*r^2;
% Stiffness and Damping matrices
K = k*eye(6);
C = c*eye(6);
% Compute plant in the frame of the struts
G_analytical = inv(ss(inv(stewart.geometry.J')*M*inv(stewart.geometry.J)*s^2 + C*s + K));
% Compare with Simscape model
initializeLoggingConfiguration('log', 'none');
initializeController('type', 'open-loop');
% Input/Output definition
clear io; io_i = 1;
io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Inputs [N]
io(io_i) = linio([mdl, '/plant'], 2, 'openoutput', [], 'dL'); io_i = io_i + 1; % Encoders [m]
G_simscape = linearize(mdl, io);
G_simscape.InputName = {'f1', 'f2', 'f3', 'f4', 'f5', 'f6'};
G_simscape.OutputName = {'dL1', 'dL2', 'dL3', 'dL4', 'dL5', 'dL6'};
#+end_src
#+begin_src matlab
bodeFig({G_analytical(1,1), G_simscape(1,1), G_analytical(1,2), G_simscape(1,2)})
#+end_src
#+begin_src matlab
initializeSimplifiedNanoHexapod('flex_type_F', '2dof', 'flex_type_M', '3dof', 'actuator_type', '1dof');
initializeSample('type', 'cylindrical', 'm', 50, 'H', 300e-3);

Binary file not shown.

View File

@ -1,4 +1,4 @@
% Created 2025-02-07 Fri 16:42
% Created 2025-02-10 Mon 14:23
% Intended LaTeX compiler: pdflatex
\documentclass[a4paper, 10pt, DIV=12, parskip=full, bibliography=totoc]{scrreprt}
@ -103,31 +103,31 @@ Kinematic Struture & Open & Closed-loop\\
\chapter{The Stewart platform}
\label{sec:nhexa_stewart_platform}
\begin{itemize}
\item Some history about Stewart platforms
\item What is so special and why it is so used in different fields: give examples
Explain advantages compared to serial architecture
\item Little review (very quick: two extreme sizes, piezo + voice coil)
Complete review of Stewart platforms will be made in Chapter 2
\item Presentation of tools used to analyze the properties of the Stewart platform => useful for design and control
\end{itemize}
The Stewart platform, first introduced by Stewart in 1965 \cite{stewart65_platf_with_six_degrees_freed} for flight simulation applications, represents a significant milestone in parallel manipulator design.
This mechanical architecture has evolved far beyond its original purpose, finding applications across diverse fields from precision positioning systems to robotic surgery.
The fundamental design consists of two platforms connected by six adjustable struts in parallel, creating a fully parallel manipulator capable of six degrees of freedom motion.
Unlike serial manipulators where errors worsen through the kinematic chain, parallel architectures distribute loads across multiple actuators, leading to enhanced mechanical stiffness and improved positioning accuracy.
This parallel configuration also results in superior dynamic performance, as the actuators directly contribute to the platform's motion without intermediate linkages.
These characteristics of Stewart platforms have made them particularly valuable in applications requiring high precision and stiffness.
The Stewart Platform is very adapted for the NASS application for the following reasons:
\begin{itemize}
\item it is a fully parallel manipulator, thus all the motions errors can be compensated
\item it is very compact compared to a serial manipulator
\item it has high stiffness and good dynamic performances
\end{itemize}
For the NASS application, the Stewart platform architecture presents three key advantages.
First, as a fully parallel manipulator, all motion errors of the micro-station can be compensated through the coordinated action of the six actuators.
Second, its compact design compared to serial manipulators makes it ideal for integration on top micro-station where only \(95\,mm\) of height is available.
Third, the good dynamical properties should enable high bandwidth positioning control.
The main disadvantage of Stewart platforms is the small workspace when compare the serial manipulators which is not a problem here.
While Stewart platforms excel in precision and stiffness, they typically exhibit a relatively limited workspace compared to serial manipulators.
However, this limitation is not significant for the NASS application, as the required motion range corresponds to the positioning errors of the micro-station which are in the order of \(10\,\mu m\).
This section provides a comprehensive analysis of the Stewart platform's properties, focusing on aspects crucial for precision positioning applications.
The analysis encompasses the platform's kinematic relationships (Section \ref{ssec:nhexa_stewart_platform_kinematics}), the use of the Jacobian matrix (Section \ref{ssec:nhexa_stewart_platform_jacobian}), static behavior (Section \ref{ssec:nhexa_stewart_platform_static}), and dynamic characteristics (Section \ref{ssec:nhexa_stewart_platform_dynamics}).
These theoretical foundations form the basis for subsequent design decisions and control strategies, which will be elaborated in later sections.
\section{Mechanical Architecture}
\label{ssec:nhexa_stewart_platform_architecture}
A Stewart manipulator consists of two platforms connected by six struts (Figure \ref{fig:nhexa_stewart_architecture}).
Each strut is connected to the fixed and the mobile platforms with a joint.
Typically, a universal joint is used on one side while a spherical joint is used on the other side\footnote{Different architecture exists, typically referred as ``6-SPS'' (Spherical, Prismatic, Spherical) or ``6-UPS'' (Universal, Prismatic, Spherical)}.
In the strut, there is an active element working as a prismatic joint.
The Stewart platform consists of two rigid platforms connected by six struts arranged in parallel (Figure \ref{fig:nhexa_stewart_architecture}).
Each strut incorporates an active prismatic joint that enables controlled length variation, with its ends attached to the fixed and mobile platforms through joints.
The typical configuration consists of a universal joint at one end and a spherical joint at the other, providing the necessary degrees of freedom\footnote{Different architecture exists, typically referred as ``6-SPS'' (Spherical, Prismatic, Spherical) or ``6-UPS'' (Universal, Prismatic, Spherical)}.
\begin{figure}[htbp]
\centering
@ -135,27 +135,21 @@ In the strut, there is an active element working as a prismatic joint.
\caption{\label{fig:nhexa_stewart_architecture}Schematical representation of the Stewart platform architecture.}
\end{figure}
Such architecture allows to move the mobile platform with respect to the fixed platform in 6 degrees-of-freedom.
It is therefore a \emph{fully} parallel manipulator as the number of actuators is equal to the number of DoF.
It is also a symmetrical parallel manipulator as typically all the struts are identical.
In order to study the Stewart platform, four important frames are typically defined:
To facilitate rigorous analysis of the Stewart platform, four reference frames are defined:
\begin{itemize}
\item \(\{F\}\): Frame fixed on the base and located at the center of its bottom surface.
This is used to fix the Stewart platform to some support.
\item \(\{M\}\): Frame fixed to the moving platform and located at the center of its top surface.
This is used to place things on top of the Stewart platform.
\item \(\{A\}\): Frame fixed to the fixed base, but located at the point-of-interest.
\item \(\{B\}\): Frame fixed to the moving platform and located at the same point-of-interest than \(\{A\}\).
\item The fixed base frame \(\{F\}\), located at the center of the base platform's bottom surface, serves as the mounting reference for the support structure.
\item The mobile frame \(\{M\}\), situated at the center of the top platform's upper surface, provides a reference for payload mounting.
\item The point-of-interest frame \(\{A\}\), fixed to the base but positioned at the workspace center.
\item The moving point-of-interest frame \(\{B\}\), attached to the mobile platform and coincident with frame \(\{A\}\) in the home position.
\end{itemize}
Frames \(\{F\}\) and \(\{M\}\) are useful to describe the location of the joints in a meaningful frame.
On the other hand, frames \(\{A\}\) and \(\{B\}\) are used to describe the relative motion of the two platforms through the position vector \({}^A\bm{P}_B\) of \(\{B\}\) expressed in \(\{A\}\) and the rotation matrix \({}^A\bm{R}_B\) expressing the orientation of \(\{B\}\) with respect to \(\{A\}\).
For the nano-hexapod, these frames are chosen to be located at the theoretical focus point of the X-ray light (\(150\,mm\) above the top platform, i.e. above \(\{M\}\)).
Frames \(\{F\}\) and \(\{M\}\) serve primarily to define the joint locations.
On the other hand, frames \(\{A\}\) and \(\{B\}\) are used to describe the relative motion of the two platforms through the position vector \({}^A\bm{P}_B\) of frame \(\{B\}\) expressed in frame \(\{A\}\) and the rotation matrix \({}^A\bm{R}_B\) expressing the orientation of \(\{B\}\) with respect to \(\{A\}\).
For the nano-hexapod, frames \(\{A\}\) and \(\{B\}\) are chosen to be located at the theoretical focus point of the X-ray light which is \(150\,mm\) above the top platform, i.e. above \(\{M\}\).
Location of the joints and orientation and length of the struts are very important for the study of the Stewart platform as well.
The center of rotation for the joint fixed to the base is noted \(\bm{a}_i\), while \(b_i\) is used for the top joints.
The struts orientation are indicated by the unit vectors \(\hat{\bm{s}}_i\) and their lengths by the scalars \(l_i\).
Location of the joints and orientation and length of the struts are crucial for subsequent kinematic, static, and dynamic analyses of the Stewart platform.
The center of rotation for the joint fixed to the base is noted \(\bm{a}_i\), while \(b_i\) is used for the top platform joints.
The struts orientation are represented by the unit vectors \(\hat{\bm{s}}_i\) and their lengths by the scalars \(l_i\).
This is summarized in Figure \ref{fig:nhexa_stewart_notations}.
\begin{figure}[htbp]
@ -166,20 +160,18 @@ This is summarized in Figure \ref{fig:nhexa_stewart_notations}.
\section{Kinematic Analysis}
\label{ssec:nhexa_stewart_platform_kinematics}
Kinematic analysis refers to the study of the geometry of motion of a robot, without considering the forces that cause the motion.
The kinematic analysis of the Stewart platform involves understanding the geometric relationships between the platform position/orientation and the actuator lengths, without considering the forces involved.
\paragraph{Loop Closure}
At the displacement level, the \emph{closure} of each kinematic loop (illustrated in Figure \ref{fig:nhexa_stewart_loop_closure}) can be express in the vector form as
\begin{equation}
\vec{ab} = \vec{aa_i} + \vec{a_ib_i} - \vec{bb_i} \quad \text{for } i = 1 \text{ to } 6
\end{equation}
in which \(\vec{aa_i}\) and \(\vec{bb_i}\) can be easily obtained from the geometry of the attachment points in the base and in the moving platform.
The foundation of the kinematic analysis lies in the geometric constraints imposed by each strut, which can be expressed through 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.
The loop closure can be written as the unknown pose variables \({}^A\bm{P}\) and \({}^A\bm{R}_B\), the position vectors describing the known geometry of the base and of the moving platform, \(\bm{a}_i\) and \(\bm{b}_i\), and the limb vector \(l_i {}^A\hat{\bm{s}}_i\):
\begin{equation}\label{eq:nhexa_loop_close}
{}^A\bm{P} = {}^A\bm{a}_i + l_i{}^A\hat{\bm{s}}_i - {}^A\bm{R}_B {}^B\bm{b}_i \quad \text{for } i=1 \text{ to } 6
\begin{equation}\label{eq:nhexa_loop_closure}
{}^A\bm{P}_B = {}^A\bm{a}_i + l_i{}^A\hat{\bm{s}}_i - \underbrace{{}^B\bm{b}_i}_{{}^A\bm{R}_B {}^B\bm{b}_i} \quad \text{for } i=1 \text{ to } 6
\end{equation}
Such equation links the pose variables \({}^A\bm{P}\) and \({}^A\bm{R}_B\), the position vectors describing the known geometry of the base and of the moving platform, \(\bm{a}_i\) and \(\bm{b}_i\), and the strut vector \(l_i {}^A\hat{\bm{s}}_i\):
\begin{figure}[htbp]
\centering
\includegraphics[scale=1]{figs/nhexa_stewart_loop_closure.png}
@ -188,10 +180,10 @@ The loop closure can be written as the unknown pose variables \({}^A\bm{P}\) and
\paragraph{Inverse Kinematics}
For \emph{inverse kinematic analysis}, it is assumed that the position \({}^A\bm{P}\) and orientation of the moving platform \({}^A\bm{R}_B\) are given and the problem is to obtain the joint variables \(\bm{\mathcal{L}} = \left[ l_1, l_2, l_3, l_4, l_5, l_6 \right]\).
This problem can be easily solved using the loop closures \eqref{eq:nhexa_loop_close}.
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\)).
This problem can be solved analytically using the loop closure equations \eqref{eq:nhexa_loop_closure}.
The obtain strut lengths are given by \eqref{eq:nhexa_inverse_kinematics}.
The obtain joint variables are:
\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}
\end{equation}
@ -201,73 +193,51 @@ Otherwise, the solution gives complex numbers.
\paragraph{Forward Kinematics}
In \emph{forward kinematic analysis}, it is assumed that the vector of limb lengths \(\bm{\mathcal{L}}\) is given and the problem is to find the position \({}^A\bm{P}\) and the orientation \({}^A\bm{R}_B\).
This is a difficult problem that requires to solve nonlinear equations.
In a next section, an approximate solution of the forward kinematics problem is proposed for small displacements.
The forward kinematic problem seeks to determine the platform pose \(\bm{\mathcal{X}}\) given a set of strut lengths \(\bm{\mathcal{L}}\).
Unlike the inverse kinematics, this presents a significant challenge as it requires solving a system of nonlinear equations.
While various numerical methods exist for solving this problem, they can be computationally intensive and may not guarantee convergence to the correct solution.
For the nano-hexapod application, where displacements are typically small, an approximate solution based on linearization around the operating point provides a practical alternative.
This approximation, developed in subsequent sections through the Jacobian matrix analysis, proves particularly useful for real-time control applications.
\section{The Jacobian Matrix}
In vector calculus, the Jacobian matrix represents the best linear approximation of a vector-valued function near a working point.
Consider a function \(\bm{f}: \mathbb{R}^n \rightarrow \mathbb{R}^m\) with continuous first-order partial derivatives.
For any input \(\bm{x} \in \mathbb{R}^n\), this function produces an output \(\bm{f}(\bm{x}) \in \mathbb{R}^m\).
The Jacobian matrix \(\bm{J}\) of \(\bm{f}\) at point \(\bm{x}\) is the \(m \times n\) matrix whose \((i,j)\) entry is:
\(J_{ij} = \frac{\partial f_i}{\partial x_j}\)
This matrix represents the linear transformation that best approximates \(\bm{f}\) in a neighborhood of \(\bm{x}\).
In other words, for points sufficiently close to \(\bm{x}\), the function \(\bm{f}\) behaves approximately like its Jacobian matrix.
\label{ssec:nhexa_stewart_platform_jacobian}
The Jacobian matrix plays a central role in analyzing the Stewart platform's behavior, providing a linear mapping between 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.
\paragraph{Jacobian Computation - Velocity Loop Closure}
Let's note:
\begin{itemize}
\item \(\bm{\mathcal{L}} = \left[ l_1, l_2, \ldots, l_6 \right]^T\): vector of actuated joint coordinates
\item \(\bm{\mathcal{X}} = \left[ {}^A\bm{P}, \bm{}^A\hat{\bm{s}} \right]^T\): vector of platform motion variables
\end{itemize}
As was shown 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.
\(\bm{\mathcal{L}}\) and \(\bm{\mathcal{X}}\) are related through a system of \emph{nonlinear algebraic equations} representing the \emph{kinematic constraints imposed by the struts}, which can be generally written as \(f(\bm{\mathcal{L}}, \bm{\mathcal{X}}) = 0\).
By taking the time derivative of the position loop close \eqref{eq:nhexa_loop_closure}, the \emph{velocity loop closure} is obtained \eqref{eq:nhexa_loop_closure_velocity}.
We can differentiate this equation with respect to time and obtain:
\begin{equation*}
\bm{J}_x \dot{\bm{\mathcal{X}}} = \bm{J}_l \dot{\bm{\mathcal{L}}} \quad \text{where} \quad
\bm{J}_x = \frac{\partial f}{\partial \bm{\mathcal{X}}} \quad \text{and} \quad \bm{J}_l = -\frac{\partial f}{\partial \bm{\mathcal{L}}}
\end{equation*}
With:
\begin{itemize}
\item \(\dot{\bm{\mathcal{L}}} = [ \dot{l}_1, \dot{l}_2, \dot{l}_3, \dot{l}_4, \dot{l}_5, \dot{l}_6 ]^T\)
\item \(\dot{\bm{X}} = [^A\bm{v}_p, {}^A\bm{\omega}]^T\):
\end{itemize}
The \textbf{general Jacobian matrix} is defined as:
\begin{equation*}
\dot{\bm{\mathcal{L}}} = \bm{J} \dot{\bm{\mathcal{X}}} \quad \text{with} \quad \bm{J} = {\bm{J}_l}^{-1} \bm{J}_x
\end{equation*}
The \textbf{velocity loop closures} are used for \textbf{obtaining the Jacobian matrices} in a straightforward manner:
\[{}^A\bm{P} + {}^A\bm{R}_B {}^B\bm{b}_i = l_i {}^A\hat{\bm{s}}_i + {}^A\bm{a}_i\]
By taking the time derivative of the position loop close \eqref{eq:nhexa_loop_close}, the velocity loop closure is obtained:
\begin{equation}
\begin{equation}\label{eq:nhexa_loop_closure_velocity}
{}^A\bm{v}_p + {}^A \dot{\bm{R}}_B {}^B\bm{b}_i + {}^A\bm{R}_B \underbrace{{}^B\dot{\bm{b}_i}}_{=0} = \dot{l}_i {}^A\hat{\bm{s}}_i + l_i {}^A\dot{\hat{\bm{s}}}_i + \underbrace{{}^A\dot{a}_i}_{=0}
\end{equation}
Moreover, we have:
\begin{itemize}
\item \({}^A\dot{\bm{R}}_B {}^B\bm{b}_i = {}^A\bm{\omega} \times {}^A\bm{R}_B {}^B\bm{b}_i = {}^A\bm{\omega} \times {}^A\bm{b}_i\) in which \({}^A\bm{\omega}\) denotes the angular velocity of the moving platform expressed in the fixed frame \(\{\bm{A}\}\).
\item \(l_i {}^A\dot{\hat{\bm{s}}}_i = l_i \left( {}^A\bm{\omega}_i \times \hat{\bm{s}}_i \right)\) in which \({}^A\bm{\omega}_i\) is the angular velocity of limb \(i\) express in fixed frame \(\{\bm{A}\}\).
\item \(l_i {}^A\dot{\hat{\bm{s}}}_i = l_i \left( {}^A\bm{\omega}_i \times \hat{\bm{s}}_i \right)\) in which \({}^A\bm{\omega}_i\) is the angular velocity of strut \(i\) express in fixed frame \(\{\bm{A}\}\).
\end{itemize}
By multiplying both sides by \({}^A\hat{s}_i\):
By multiplying both sides by \({}^A\hat{s}_i\), \eqref{eq:nhexa_loop_closure_velocity_bis} is obtained.
\begin{equation}
\begin{equation}\label{eq:nhexa_loop_closure_velocity_bis}
{}^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}
Finally:
\begin{equation}
\hat{\bm{s}}_i {}^A\bm{v}_p + ({}^A\bm{b}_i \times \hat{\bm{s}}_i) {}^A\bm{\omega} = \dot{l}_i
Equation \eqref{eq:nhexa_loop_closure_velocity_bis} can be rearranged in a 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.
\begin{equation}\label{eq:nhexa_jacobian_velocities}
\boxed{\dot{\bm{\mathcal{L}}} = \bm{J} \dot{\bm{\mathcal{X}}}}
\end{equation}
We can rearrange the equations in a matrix form:
\[ \dot{\bm{\mathcal{L}}} = \bm{J} \dot{\bm{\mathcal{X}}} \quad \text{with} \ \dot{\bm{\mathcal{L}}} = [ \dot{l}_1 \ \dots \ \dot{l}_6 ]^T \ \text{and} \ \dot{\bm{\mathcal{X}}} = [{}^A\bm{v}_p ,\ {}^A\bm{\omega}]^T \]
The matrix \(\bm{J}\) is called the Jacobian matrix, and is defined by \eqref{eq:nhexa_jacobian}, with:
\begin{itemize}
\item \(\hat{\bm{s}}_i\) the orientation of the struts expressed in \(\{A\}\)
\item \(\bm{b}_i\) the position of the joints with respect to \(O_B\) and express in \(\{A\}\)
\end{itemize}
\begin{equation}\label{eq:nhexa_jacobian}
\bm{J} = \begin{bmatrix}
@ -280,23 +250,17 @@ We can rearrange the equations in a matrix form:
\end{bmatrix}
\end{equation}
\(\bm{J}\) then depends only on:
\begin{itemize}
\item \(\hat{\bm{s}}_i\) the orientation of the limbs expressed in \(\{A\}\)
\item \(\bm{b}_i\) the position of the joints with respect to \(O_B\) and express in \(\{A\}\)
\end{itemize}
The Jacobian matrix links the rate of change of strut length to the velocity and angular velocity of the top platform with respect to the fixed base.
This Jacobian matrix needs to be recomputed for every Stewart platform pose.
This Jacobian matrix \(\bm{J}\) therefore links the rate of change of 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 as it depends on the actual pose of of the manipulator.
\paragraph{Approximate solution of the Forward and Inverse Kinematic problems}
For small displacements mobile platform displacement \(\delta \bm{\mathcal{X}} = [\delta x, \delta y, \delta z, \delta \theta_x, \delta \theta_y, \delta \theta_z ]^T\) around \(\bm{\mathcal{X}}_0\), the associated joint displacement can be computed using the Jacobian (approximate solution of the inverse kinematic problem):
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 (approximate solution of the inverse kinematic problem):
\begin{equation}\label{eq:nhexa_inverse_kinematics_approximate}
\boxed{\delta\bm{\mathcal{L}} = \bm{J} \delta\bm{\mathcal{X}}}
\end{equation}
Similarly, for small joint displacements \(\delta\bm{\mathcal{L}} = [ \delta l_1,\ \dots,\ \delta l_6 ]^T\) around \(\bm{\mathcal{L}}_0\), it is possible to find the induced small displacement of the mobile platform (approximate solution of the forward kinematic problem):
Similarly, for small joint displacements \(\delta\bm{\mathcal{L}}\), it is possible to find the induced small displacement of the mobile platform (approximate solution of the forward kinematic problem):
\begin{equation}\label{eq:nhexa_forward_kinematics_approximate}
\boxed{\delta\bm{\mathcal{X}} = \bm{J}^{-1} \delta\bm{\mathcal{L}}}
\end{equation}
@ -306,98 +270,161 @@ As the inverse kinematic can be easily solved exactly this is not much useful, h
\paragraph{Range validity of the approximate inverse kinematics}
The accuracy of the Jacobian-based forward kinematics solution was estimated through a systematic error analysis.
For a series of platform positions along the \$x\$-axis, the exact strut lengths are computed using the analytical inverse kinematics equation \eqref{eq:nhexa_inverse_kinematics}.
These strut lengths are then used with the Jacobian to estimate the platform pose, from which the error between the estimated and true poses can be calculated.
As we know how to exactly solve the Inverse kinematic problem, we can compare the exact solution with the approximate solution using the Jacobian matrix.
For small displacements, the approximate solution is expected to work well.
We would like here to determine up to what displacement this approximation can be considered as correct.
The estimation errors in the \(x\), \(y\), and \(z\) directions are shown in Figure \ref{fig:nhexa_forward_kinematics_approximate_errors}.
The results demonstrate that for displacements up to approximately \(1\,\%\) of the hexapod's size (which corresponds to \(100\,\mu m\) as the size of the Stewart platform is here \(\approx 100\,mm\)), the Jacobian approximation provides excellent accuracy.
Then, we can determine the range for which the approximate inverse kinematic is valid.
This will also gives us the range for which the approximate forward kinematic is valid.
This finding has particular significance for the Nano-hexapod application.
Since the maximum required stroke (\(\approx 100\,\mu m\)) is three orders of magnitude smaller than the stewart platform size (\(\approx 100\,mm\)), the Jacobian matrix can be considered constant throughout the workspace.
It can be computed once at the rest position and used for both forward and inverse kinematics with high accuracy.
\begin{itemize}
\item[{$\square$}] \href{file:///home/thomas/Cloud/work-projects/ID31-NASS/matlab/stewart-simscape/org/kinematic-study.org}{Estimation of the range validity of the approximate inverse kinematics}
\end{itemize}
Let's first compare the perfect and approximate solution of the inverse for pure \(x\) translations.
The approximate and exact required strut stroke to have the wanted mobile platform \(x\) displacement are computed.
The estimated error is shown in Figure etc\ldots{}
For small wanted displacements (up to \(\approx 1\%\) of the size of the Hexapod), the approximate inverse kinematic solution using the Jacobian matrix is quite correct.
In the case of the Nano-hexapod, the maximum stroke is estimate to the around \(100\,\mu m\) while its size is around \(100\,mm\), therefore the fixed Jacobian matrix is a very good approximate for the forward and inverse kinematics.
\begin{figure}[htbp]
\centering
\includegraphics[scale=1]{figs/nhexa_forward_kinematics_approximate_errors.png}
\caption{\label{fig:nhexa_forward_kinematics_approximate_errors}Errors associated with the use of the Jacobian matrix to solve the forward kinematic problem}
\end{figure}
\paragraph{Static Forces}
Let's note \(\bm{\tau} = [\tau_1, \tau_2, \cdots, \tau_6]^T\) the vector of actuator forces applied in each strut and \(\bm{\mathcal{F}} = [\bm{f}, \bm{n}]^T\) external force/torque action on the mobile platform at \(\bm{O}_B\).
The static force analysis of the Stewart platform can be elegantly 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.
The \emph{principle of virtual work} states that the total virtual work \(\delta W\), done by all actuators and external forces is equal to zero:
Let \(\bm{\tau} = [\tau_1, \tau_2, \cdots, \tau_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\).
The virtual work \(\delta W\) consists of two contributions:
\begin{itemize}
\item The work performed by the actuator forces through virtual strut displacements \(\delta \bm{\mathcal{L}}\): \(\bm{\tau}^T \delta \bm{\mathcal{L}}\)
\item The work performed by the external wrench through virtual platform displacements \(\delta \bm{\mathcal{X}}\): \(-\bm{\mathcal{F}}^T \delta \bm{\mathcal{X}}\)
\end{itemize}
The principle of virtual work can thus be expressed as:
\begin{equation}
\delta W = \bm{\tau}^T \delta \bm{\mathcal{L}} - \bm{\mathcal{F}}^T \delta \bm{\mathcal{X}} = 0
\delta W = \bm{\tau}^T \delta \bm{\mathcal{L}} - \bm{\mathcal{F}}^T \delta \bm{\mathcal{X}} = 0
\end{equation}
From the definition of the Jacobian (\(\delta \bm{\mathcal{L}} = \bm{J} \cdot \delta \bm{\mathcal{X}}\)), we have \(\left( \bm{\tau}^T \bm{J} - \bm{\mathcal{F}}^T \right) \delta \bm{\mathcal{X}} = 0\) that holds for any \(\delta \bm{\mathcal{X}}\), hence:
Using the Jacobian relationship that links virtual displacements \eqref{eq:nhexa_inverse_kinematics_approximate}, this equation becomes:
\begin{equation}
\left( \bm{\tau}^T \bm{J} - \bm{\mathcal{F}}^T \right) \delta \bm{\mathcal{X}} = 0
\end{equation}
Since this equation must hold for any virtual displacement \(\delta \bm{\mathcal{X}}\), the following force mapping relationships can be derived:
\begin{equation}\label{eq:nhexa_jacobian_forces}
\bm{\tau}^T \bm{J} - \bm{\mathcal{F}}^T = 0 \quad \Rightarrow \quad \boxed{\bm{\mathcal{F}} = \bm{J}^T \bm{\tau}} \quad \text{and} \quad \boxed{\bm{\tau} = \bm{J}^{-T} \bm{\mathcal{F}}}
\end{equation}
Therefore, the same Jacobian matrix can also be used to map actuator forces to forces and torques applied on the mobile platform at the defined frame \(\{B\}\).
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.
\section{Static Analysis}
\label{ssec:nhexa_stewart_platform_static}
How stiffness varies with orientation of struts.
Same with stroke?
Or maybe in the detailed chapter?
The static stiffness characteristics of the Stewart platform play a crucial role in its performance, particularly for precision positioning applications.
These characteristics are fundamentally determined by both the actuator properties and the platform geometry.
The stiffness of the actuator \(k_i\) links the applied actuator force \(\delta \tau_i\) and the corresponding small deflection \(\delta l_i\):
\begin{equation*}
\tau_i = k_i \delta l_i, \quad i = 1,\ \dots,\ 6
\end{equation*}
If we combine these 6 relations:
\begin{equation*}
\bm{\tau} = \mathcal{K} \delta \bm{\mathcal{L}} \quad \mathcal{K} = \text{diag}\left[ k_1,\ \dots,\ k_6 \right]
\end{equation*}
Starting from the individual actuators, the relationship between applied force \(\delta \tau_i\) and resulting displacement \(\delta l_i\) for each strut \(i\) is characterized by its stiffness \(k_i\):
\begin{equation}
\tau_i = k_i \delta l_i, \quad i = 1,\ \dots,\ 6
\end{equation}
Substituting \(\bm{\tau} = \bm{J}^{-T} \bm{\mathcal{F}}\) and \(\delta \bm{\mathcal{L}} = \bm{J} \cdot \delta \bm{\mathcal{X}}\) gives
\begin{equation*}
\bm{\mathcal{F}} = \bm{J}^T \mathcal{K} \bm{J} \cdot \delta \bm{\mathcal{X}}
\end{equation*}
And then we identify the stiffness matrix \(\bm{K}\):
\begin{equation*}
\bm{K} = \bm{J}^T \mathcal{K} \bm{J}
\end{equation*}
These individual relationships can be combined into a matrix form using the diagonal stiffness matrix \(\mathcal{K}\):
\begin{equation}
\bm{\tau} = \mathcal{K} \delta \bm{\mathcal{L}}, \quad \mathcal{K} = \text{diag}\left[ k_1,\ \dots,\ k_6 \right]
\end{equation}
If the stiffness matrix \(\bm{K}\) is inversible, the \textbf{compliance matrix} of the manipulator is defined as
\begin{equation*}
\bm{C} = \bm{K}^{-1} = (\bm{J}^T \mathcal{K} \bm{J})^{-1}
\end{equation*}
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}.
The compliance matrix of a manipulator shows the mapping of the moving platform wrench applied at \(\bm{O}_B\) to its small deflection by
\begin{equation*}
\delta \bm{\mathcal{X}} = \bm{C} \cdot \bm{\mathcal{F}}
\end{equation*}
\begin{equation}\label{eq:nhexa_stiffness_matrix}
\bm{\mathcal{F}} = \underbrace{\bm{J}^T \mathcal{K} \bm{J}}_{\bm{K}} \delta \bm{\mathcal{X}}
\end{equation}
where \(\bm{K} = \bm{J}^T \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 \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:
\begin{itemize}
\item The individual actuator stiffnesses represented by \(\mathcal{K}\)
\item The geometric configuration embodied in the Jacobian matrix \(\bm{J}\)
\end{itemize}
This geometric dependency means that the platform's stiffness varies throughout its workspace, as the Jacobian matrix changes with the platform's position and orientation.
For the NASS application, where the workspace is relatively small compared to the platform dimensions, these variations can be considered minimal.
However, the initial geometric configuration significantly impacts the overall stiffness characteristics.
The relationship between maximum stroke and stiffness presents another important design consideration.
As both parameters are influenced by the geometric configuration, their optimization involves inherent trade-offs that must be carefully balanced based on application requirements.
The optimization of this configuration to achieve desired stiffness properties while having enough stroke will be addressed during the detailed design phase.
\section{Dynamic Analysis}
\label{ssec:nhexa_stewart_platform_dynamics}
Very complex => multi-body model
For instance, compute the plant for massless struts and perfect joints (will be compared with Simscape model).
But say that if we want to model more complex cases, it becomes impractical (cite papers).
The dynamic behavior of a Stewart platform can be analyzed through various approaches, depending on the desired level of model fidelity.
For initial analysis, we consider a simplified model with the following assumptions:
\begin{itemize}
\item Massless struts
\item Ideal joints without friction or compliance
\item Rigid platform and base
\end{itemize}
Under these assumptions, the system dynamics can be expressed in the Cartesian space as:
\begin{equation}
M s^2 \mathcal{X} = \Sigma \mathcal{F}
\end{equation}
where \(M\) represents the platform mass matrix, \(\mathcal{X}\) the platform pose, and \(\Sigma \mathcal{F}\) the sum of forces acting on the platform.
The primary forces acting on the system are actuator forces \(\bm{\tau}\), elastic forces due to strut stiffness \(-\mathcal{K} \mathcal{L}\) and damping forces in the struts \(\mathcal{C} \dot{\mathcal{L}}\).
\begin{equation}
\Sigma \bm{\mathcal{F}} = \bm{J}^T (\tau - \mathcal{K} \mathcal{L} - s \mathcal{C} \mathcal{L}), \quad \mathcal{K} = \text{diag}(k_1\,\dots\,k_6),\ \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}
M s^2 \mathcal{X} = \mathcal{F} - J^T \mathcal{K} J \mathcal{X} - J^T \mathcal{C} J s \mathcal{X}
\end{equation}
The transfer function in the Cartesian frame becomes \eqref{eq:nhexa_transfer_function_cart}.
\begin{equation}\label{eq:nhexa_transfer_function_cart}
\frac{\mathcal{X}}{\mathcal{F}}(s) = ( M s^2 + \bm{J}^{T} \mathcal{C} J s + \bm{J}^{T} \mathcal{K} 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}.
\begin{equation}\label{eq:nhexa_transfer_function_struts}
\frac{\mathcal{L}}{\tau}(s) = ( \bm{J}^{-T} M \bm{J}^{-1} s^2 + \mathcal{C} + \mathcal{K} )^{-1}
\end{equation}
While this simplified model provides useful insights, real Stewart platforms exhibit more complex behaviors.
Several factors significantly increase model complexity:
\begin{itemize}
\item Strut dynamics, including mass distribution and internal resonances
\item Joint compliance and friction effects
\item Supporting structure dynamics and payload dynamics, which are both very critical for NASS
\end{itemize}
These additional effects make analytical modeling impractical for complete system analysis.
\section*{Conclusion}
Dynamic analysis of parallel manipulators presents an \textbf{inherent complexity due to their closed-loop structure and kinematic constraints}.
The fundamental characteristics of the Stewart platform have been analyzed in this chapter.
Essential kinematic relationships were developed through loop closure equations, from which both exact and approximate solutions for the inverse and forward kinematic problems were derived.
The Jacobian matrix was established as a central mathematical tool, through which crucial insights into velocity relationships, static force transmission, and dynamic behavior of the platform were obtained.
All depends on the geometry.
Reasonable choice of geometry is made in chapter 1.
Optimization of the geometry will be made in chapter 2.
For the NASS application, where displacements are typically limited to the micrometer range, the accuracy of linearized models using a constant Jacobian matrix has been demonstrated, by which both analysis and control can be significantly simplified.
However, additional complexities such as strut masses, joint compliance, and supporting structure dynamics must be considered in the full dynamic behavior.
This will be performed in the next section using a multi-body model.
All these characteristics (maneuverability, stiffness, dynamics, etc.) are fundamentally determined by the platform's geometry.
While a reasonable geometric configuration will be used to validate the NASS during this conceptual phase, the optimization of these geometric parameters will be explored during the detailed design phase.
\chapter{Multi-Body Model}
\label{sec:nhexa_model}
\textbf{Goal}:
\begin{itemize}
\item Study the dynamics of Stewart platform
\item Instead of working with complex analytical models: a multi-body model is used.
@ -405,8 +432,6 @@ Complex because has to model the inertia of the struts.
Cite papers that tries to model the stewart platform analytically
Advantage: it will be easily included in the model of the NASS
\item Mention the Toolbox (maybe make a DOI for that)
\item[{$\square$}] Have a table somewhere that summarizes the main characteristics of the nano-hexapod model
\begin{itemize}
\item location of joints