Add configuration for added parallel stiffness

This commit is contained in:
Thomas Dehaeze 2025-02-10 16:31:23 +01:00
parent a7f85ba00b
commit 8153a9d87b
6 changed files with 156 additions and 51 deletions

Binary file not shown.

View File

@ -29,13 +29,16 @@ fprintf('ACTUATORS:\n')
if stewart.actuators.type == 1
fprintf('- The actuators are modelled as 1DoF.\n')
fprintf('- The Stiffness and Damping of each actuators is:\n')
fprintf('\t k = %.0e [N/m] \t c = %.0e [N/(m/s)]\n', stewart.actuators.K(1), stewart.actuators.C(1))
fprintf('\t k = %.0e [N/m] \t c = %.0e [N/(m/s)]\n', stewart.actuators.k(1), stewart.actuators.c(1))
if stewart.actuators.kp > 0
fprintf('\t Added parallel stiffness: kp = %.0e [N/m] \t c = %.0e [N/(m/s)]\n', stewart.actuators.kp(1))
end
elseif stewart.actuators.type == 2
fprintf('- The actuators are modelled as 2DoF (APA).\n')
fprintf('- The vertical stiffness and damping contribution of the piezoelectric stack is:\n')
fprintf('\t ka = %.0e [N/m] \t ca = %.0e [N/(m/s)]\n', stewart.actuators.Ka(1), stewart.actuators.Ca(1))
fprintf('\t ka = %.0e [N/m] \t ca = %.0e [N/(m/s)]\n', stewart.actuators.ka(1), stewart.actuators.ca(1))
fprintf('- Vertical stiffness when the piezoelectric stack is removed is:\n')
fprintf('\t kr = %.0e [N/m] \t cr = %.0e [N/(m/s)]\n', stewart.actuators.Kr(1), stewart.actuators.Cr(1))
fprintf('\t kr = %.0e [N/m] \t cr = %.0e [N/(m/s)]\n', stewart.actuators.kr(1), stewart.actuators.cr(1))
elseif stewart.actuators.type == 3
fprintf('- The actuators are modelled with a flexible element (FEM).\n')
end

View File

@ -5,18 +5,20 @@ function [nano_hexapod] = initializeSimplifiedNanoHexapod(args)
args.H (1,1) double {mustBeNumeric, mustBePositive} = 95e-3 % Height of the nano-hexapod [m]
args.MO_B (1,1) double {mustBeNumeric} = 150e-3 % Height of {B} w.r.t. {M} [m]
%% generateGeneralConfiguration
args.FH (1,1) double {mustBeNumeric, mustBePositive} = 20e-3 % Height of fixed joints [m]
args.FH (1,1) double {mustBeNumeric, mustBePositive} = 15e-3 % Height of fixed joints [m]
args.FR (1,1) double {mustBeNumeric, mustBePositive} = 120e-3 % Radius of fixed joints [m]
args.FTh (6,1) double {mustBeNumeric} = [220, 320, 340, 80, 100, 200]*(pi/180) % Angles of fixed joints [rad]
args.MH (1,1) double {mustBeNumeric, mustBePositive} = 20e-3 % Height of mobile joints [m]
args.MH (1,1) double {mustBeNumeric, mustBePositive} = 15e-3 % Height of mobile joints [m]
args.MR (1,1) double {mustBeNumeric, mustBePositive} = 110e-3 % Radius of mobile joints [m]
args.MTh (6,1) double {mustBeNumeric} = [255, 285, 15, 45, 135, 165]*(pi/180) % Angles of fixed joints [rad]
%% Actuators
args.actuator_type char {mustBeMember(args.actuator_type,{'1dof', '2dof', 'flexible'})} = '1dof'
args.actuator_k (1,1) double {mustBeNumeric, mustBePositive} = 380000
args.actuator_kp (1,1) double {mustBeNumeric, mustBeNonnegative} = 0
args.actuator_ke (1,1) double {mustBeNumeric, mustBePositive} = 4952605
args.actuator_ka (1,1) double {mustBeNumeric, mustBePositive} = 2476302
args.actuator_c (1,1) double {mustBeNumeric, mustBePositive} = 5
args.actuator_cp (1,1) double {mustBeNumeric, mustBeNonnegative} = 0
args.actuator_ce (1,1) double {mustBeNumeric, mustBePositive} = 100
args.actuator_ca (1,1) double {mustBeNumeric, mustBePositive} = 50
%% initializeCylindricalPlatforms
@ -76,9 +78,11 @@ function [nano_hexapod] = initializeSimplifiedNanoHexapod(args)
stewart = initializeStrutDynamics(stewart, ...
'type', args.actuator_type, ...
'k', args.actuator_k, ...
'kp', args.actuator_kp, ...
'ke', args.actuator_ke, ...
'ka', args.actuator_ka, ...
'c', args.actuator_c, ...
'cp', args.actuator_cp, ...
'ce', args.actuator_ce, ...
'ca', args.actuator_ca);

View File

@ -18,9 +18,11 @@ function [stewart] = initializeStrutDynamics(stewart, args)
stewart
args.type char {mustBeMember(args.type,{'1dof', '2dof', 'flexible'})} = '1dof'
args.k (1,1) double {mustBeNumeric, mustBeNonnegative} = 20e6
args.kp (1,1) double {mustBeNumeric, mustBeNonnegative} = 0
args.ke (1,1) double {mustBeNumeric, mustBeNonnegative} = 5e6
args.ka (1,1) double {mustBeNumeric, mustBeNonnegative} = 60e6
args.c (1,1) double {mustBeNumeric, mustBeNonnegative} = 2e1
args.cp (1,1) double {mustBeNumeric, mustBeNonnegative} = 0
args.ce (1,1) double {mustBeNumeric, mustBeNonnegative} = 1e6
args.ca (1,1) double {mustBeNumeric, mustBeNonnegative} = 10
@ -40,6 +42,10 @@ function [stewart] = initializeStrutDynamics(stewart, args)
stewart.actuators.k = args.k;
stewart.actuators.c = args.c;
% Parallel stiffness
stewart.actuators.kp = args.kp;
stewart.actuators.cp = args.cp;
stewart.actuators.ka = args.ka;
stewart.actuators.ca = args.ca;

Binary file not shown.

View File

@ -211,6 +211,15 @@ CLOSED: [2025-02-05 Wed 16:04]
- control is performed
- simulations => validation of the concept
** QUES [#A] Should I talk about APA here?
- It seems APA is not mentioned in chapter 1
- Could be nice to only talk about APA in chapter 2 as in chapter 1 we don't care too much about actual implementation/design
- [ ] Should the NASS be validated using 1 DoF actuators?
How to deal with IFF?
- Add parallel stiffness
- High pass filter
** TODO [#A] Make sure the Simulink file for the Stewart platform is working well
SCHEDULED: <2025-02-10 Mon>
@ -246,7 +255,13 @@ It should be the exact model reference that will be included in the NASS model (
- [X] Log configuration
- [ ] *Do I want to be able to change each individual parameter value of each strut => no*
** TODO [#C] Better understand principle of virtual work
** TODO [#B] Check all notations
- [ ] Make sure they are all defined in correct order
- [ ] Make sure all vectors and matrices are bold
** DONE [#C] Better understand principle of virtual work
CLOSED: [2025-02-10 Mon 15:51]
[[*Static Forces][Static Forces]]
@ -254,7 +269,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)
** 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]
@ -550,17 +565,17 @@ Equation eqref:eq:nhexa_loop_closure_velocity_bis can be rearranged in a matrix
\end{equation}
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\}$
- ${}^A\hat{\bm{s}}_i$ the orientation of the struts expressed in $\{A\}$
- ${}^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}
{\hat{\bm{s}}_1}^T & (\bm{b}_1 \times \hat{\bm{s}}_1)^T \\
{\hat{\bm{s}}_2}^T & (\bm{b}_2 \times \hat{\bm{s}}_2)^T \\
{\hat{\bm{s}}_3}^T & (\bm{b}_3 \times \hat{\bm{s}}_3)^T \\
{\hat{\bm{s}}_4}^T & (\bm{b}_4 \times \hat{\bm{s}}_4)^T \\
{\hat{\bm{s}}_5}^T & (\bm{b}_5 \times \hat{\bm{s}}_5)^T \\
{\hat{\bm{s}}_6}^T & (\bm{b}_6 \times \hat{\bm{s}}_6)^T
{{}^A\hat{\bm{s}}_1}^T & ({}^A\bm{b}_1 \times {}^A\hat{\bm{s}}_1)^T \\
{{}^A\hat{\bm{s}}_2}^T & ({}^A\bm{b}_2 \times {}^A\hat{\bm{s}}_2)^T \\
{{}^A\hat{\bm{s}}_3}^T & ({}^A\bm{b}_3 \times {}^A\hat{\bm{s}}_3)^T \\
{{}^A\hat{\bm{s}}_4}^T & ({}^A\bm{b}_4 \times {}^A\hat{\bm{s}}_4)^T \\
{{}^A\hat{\bm{s}}_5}^T & ({}^A\bm{b}_5 \times {}^A\hat{\bm{s}}_5)^T \\
{{}^A\hat{\bm{s}}_6}^T & ({}^A\bm{b}_6 \times {}^A\hat{\bm{s}}_6)^T
\end{bmatrix}
\end{equation}
@ -638,7 +653,7 @@ exportFig('figs/nhexa_forward_kinematics_approximate_errors.pdf', 'width', 'wide
#+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
#+caption: Errors associated with the use of the Jacobian matrix to solve the forward kinematic problem. A Stewart platform with an height of $100\,mm$ was used to perform this analysis
#+RESULTS:
[[file:figs/nhexa_forward_kinematics_approximate_errors.png]]
@ -670,7 +685,7 @@ Since this equation must hold for any virtual displacement $\delta \bm{\mathcal{
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.
** TODO Static Analysis
** Static Analysis
<<ssec:nhexa_stewart_platform_static>>
The static stiffness characteristics of the Stewart platform play a crucial role in its performance, particularly for precision positioning applications.
@ -790,10 +805,6 @@ While a reasonable geometric configuration will be used to validate the NASS dur
Cite papers that tries to model the stewart platform analytically
Advantage: it will be easily included in the model of the NASS
- [ ] Have a table somewhere that summarizes the main characteristics of the nano-hexapod model
- location of joints
- size / mass of platforms, etc...
** Matlab Init :noexport:ignore:
#+begin_src matlab :tangle no :exports none :results silent :noweb yes :var current_dir=(file-name-directory buffer-file-name)
<<matlab-dir>>
@ -821,43 +832,99 @@ While a reasonable geometric configuration will be used to validate the NASS dur
** Model Definition
<<ssec:nhexa_model_def>>
**** Geometry
- [ ] Make a schematic of the definition process (for instance knowing the ai, bi points + {A} and {B} allows to compute Jacobian, etc...)
#+begin_src matlab
nano_hexapod = initializeSimplifiedNanoHexapod();
#+end_src
- What is important for the model:
- Inertia of plates and struts
- Positions of joints / Orientation of struts
- Definition of frames (for Jacobian, stiffness analysis, etc...)
The geometry of the Stewart platform (see Figure ref:fig:nhexa_stewart_model_def) is defined by the position of frame $\{F\}$ with respect to $\{M\}$ and by the locations of the joints ${}^Fa_i$ and ${}^Mb_i$.
The point of interest, indicated by frame $\{A\}$ is located $150\,mm$ above the top platform (i.e. above the $\{M\}$ frame).
Parameters that defines the geometry of the nano-hexapod multi-body models are summarized in Table ref:tab:nhexa_stewart_model_geometry.
Then, several things can be computed:
- Kinematics, stiffness, platform mobility, dynamics, etc...
From this, the orientation $\hat{s}_i$ and length $l_i$ of the struts can be computed, the Jacobian matrix $\bm{J}$ can be computed, and the kinematics of the Stewart platform can be studied.
#+attr_latex: :options [b]{0.6\linewidth}
#+begin_minipage
#+name: fig:nhexa_stewart_model_def
#+caption: Geometry of the stewart platform
#+attr_latex: :float nil :scale 1
[[file:figs/nhexa_stewart_model_def.png]]
#+end_minipage
\hfill
#+attr_latex: :options [b]{0.38\linewidth}
#+begin_minipage
#+begin_scriptsize
#+latex: \centering
#+attr_latex: :environment tabularx :width 0.75\linewidth :placement [b] :align Xrrr
#+attr_latex: :booktabs t :float nil :center nil
| | $\bm{x}$ | $\bm{y}$ | $\bm{z}$ |
|-----------+----------+----------+----------|
| ${}^MO_B$ | $0$ | $0$ | $150$ |
| ${}^FO_M$ | $0$ | $0$ | $95$ |
| ${}^Fa_1$ | $-92$ | $-77$ | $20$ |
| ${}^Fa_2$ | $92$ | $-77$ | $20$ |
| ${}^Fa_3$ | $113$ | $-41$ | $20$ |
| ${}^Fa_4$ | $21$ | $118$ | $20$ |
| ${}^Fa_5$ | $-21$ | $118$ | $20$ |
| ${}^Fa_6$ | $-113$ | $-41$ | $20$ |
| ${}^Mb_1$ | $-28$ | $-106$ | $-20$ |
| ${}^Mb_2$ | $28$ | $-106$ | $-20$ |
| ${}^Mb_3$ | $106$ | $28$ | $-20$ |
| ${}^Mb_4$ | $78$ | $78$ | $-20$ |
| ${}^Mb_5$ | $-78$ | $78$ | $-20$ |
| ${}^Mb_6$ | $-106$ | $28$ | $-20$ |
#+latex: \captionof{table}{\label{tab:nhexa_stewart_model_geometry}Parameter values in [mm]}
#+end_scriptsize
#+end_minipage
**** Inertia of Plates
Both the fixed base and the top platform are modelled are solid bodies.
The bottom plate is a cylinder with radius of $120\,mm$ (matching the size of the micro-hexapod's top platform) and a thickness of $15\,mm$.
The top plate is also modelled as a cylinder with a radius of $110\,mm$ and a thickness of $15,mm$.
Both have a mass of $5\,kg$.
**** Joints
The top and bottom joints, different number of DoF can be considered.
universal joint, spherical joint, with added axial stiffness and even with added lateral stiffnesses.
For each DoF, stiffnesses can be added.
During the conceptual design phase, bottom joints are modelled with universal joints (2-DoF) while top joints are modelled with spherical joints (3-DoF).
Both have no stiffness along their DoF and are mass-less.
**** Actuators
In its simplest form, the actuators are modelled with one prismatic joint having some internal stiffness and damping.
As was shown
- [ ] Add schematic of the 1DoF model (possibly with added parallel stiffness)
- [ ] Add model parameters for the 2DoF actuator used for the model (choose something reasonable for an APA)
- Joints: can be 2dof to 6dof
- Actuators: can be modelled as wanted
- Talk about 2DoF and 1DoF
** Nano Hexapod
<<ssec:nhexa_model_nano_hexapod>>
Start simple:
- Perfect joints, massless actuators
Joints: perfect 2dof/3dof (+ mass-less)
Actuators: APA + Encoder (mass-less)
During the conceptual design: Actuators = 1DoF + Encoder (mass-less)
- k = 1N/um
- Force sensor
Definition of each part + Plant with defined inputs/outputs (force sensor, relative displacement sensor, etc...)
** Model Dynamics
<<ssec:nhexa_model_dynamics>>
- [ ] Make schematic with inputs and outputs (maybe add frames {F} and {M} to connect to outside world)
- [ ] Screenshot of the obtained multi-body model ?
- If all is perfect (mass-less struts, perfect joints, etc...), maybe compare analytical model with simscape model?
- Say something about the model order
Model order is 12, and that we can compute modes from matrices M and K, compare with the Simscape model
- 4 observed modes (due to symmetry, in reality 6 modes)
- Compare with analytical formulas (see number of states)
- Effect of 2DoF APA on IFF plant?
- [ ] Effect of parallel on IFF plant?
#+begin_src matlab
%% Plant using Analytical Equations
@ -865,7 +932,13 @@ Definition of each part + Plant with defined inputs/outputs (force sensor, relat
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);
stewart = initializeSimplifiedNanoHexapod(...
'Mpm', 1e-3, ...
'actuator_type', '1dof', ...
'actuator_k', k, ...
'actuator_kp', 1e4, ...
'actuator_c', c ...
);
% Payload: Cylinder
h = 300e-3; % Height of the cylinder [m]
@ -908,11 +981,11 @@ 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);
% initializeSimplifiedNanoHexapod('flex_type_F', '2dof', 'flex_type_M', '3dof', 'actuator_type', '1dof');
% initializeSample('type', 'cylindrical', 'm', 50, 'H', 300e-3);
initializeLoggingConfiguration('log', 'none');
initializeController('type', 'open-loop');
% initializeLoggingConfiguration('log', 'none');
% initializeController('type', 'open-loop');
% Input/Output definition
clear io; io_i = 1;
@ -1011,10 +1084,16 @@ linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
#+end_src
** Nano Hexapod
#+begin_src matlab
initializeSimplifiedNanoHexapod();
#+end_src
** Conclusion
:PROPERTIES:
:UNNUMBERED: t
:END:
:properties:
:unnumbered: t
:end:
- Validation of multi-body model in a simple case
- Possible to increase the model complexity when required
@ -1360,18 +1439,20 @@ function [nano_hexapod] = initializeSimplifiedNanoHexapod(args)
args.H (1,1) double {mustBeNumeric, mustBePositive} = 95e-3 % Height of the nano-hexapod [m]
args.MO_B (1,1) double {mustBeNumeric} = 150e-3 % Height of {B} w.r.t. {M} [m]
%% generateGeneralConfiguration
args.FH (1,1) double {mustBeNumeric, mustBePositive} = 20e-3 % Height of fixed joints [m]
args.FH (1,1) double {mustBeNumeric, mustBePositive} = 15e-3 % Height of fixed joints [m]
args.FR (1,1) double {mustBeNumeric, mustBePositive} = 120e-3 % Radius of fixed joints [m]
args.FTh (6,1) double {mustBeNumeric} = [220, 320, 340, 80, 100, 200]*(pi/180) % Angles of fixed joints [rad]
args.MH (1,1) double {mustBeNumeric, mustBePositive} = 20e-3 % Height of mobile joints [m]
args.MH (1,1) double {mustBeNumeric, mustBePositive} = 15e-3 % Height of mobile joints [m]
args.MR (1,1) double {mustBeNumeric, mustBePositive} = 110e-3 % Radius of mobile joints [m]
args.MTh (6,1) double {mustBeNumeric} = [255, 285, 15, 45, 135, 165]*(pi/180) % Angles of fixed joints [rad]
%% Actuators
args.actuator_type char {mustBeMember(args.actuator_type,{'1dof', '2dof', 'flexible'})} = '1dof'
args.actuator_k (1,1) double {mustBeNumeric, mustBePositive} = 380000
args.actuator_kp (1,1) double {mustBeNumeric, mustBeNonnegative} = 0
args.actuator_ke (1,1) double {mustBeNumeric, mustBePositive} = 4952605
args.actuator_ka (1,1) double {mustBeNumeric, mustBePositive} = 2476302
args.actuator_c (1,1) double {mustBeNumeric, mustBePositive} = 5
args.actuator_cp (1,1) double {mustBeNumeric, mustBeNonnegative} = 0
args.actuator_ce (1,1) double {mustBeNumeric, mustBePositive} = 100
args.actuator_ca (1,1) double {mustBeNumeric, mustBePositive} = 50
%% initializeCylindricalPlatforms
@ -1431,9 +1512,11 @@ function [nano_hexapod] = initializeSimplifiedNanoHexapod(args)
stewart = initializeStrutDynamics(stewart, ...
'type', args.actuator_type, ...
'k', args.actuator_k, ...
'kp', args.actuator_kp, ...
'ke', args.actuator_ke, ...
'ka', args.actuator_ka, ...
'c', args.actuator_c, ...
'cp', args.actuator_cp, ...
'ce', args.actuator_ce, ...
'ca', args.actuator_ca);
@ -1851,9 +1934,11 @@ function [stewart] = initializeStrutDynamics(stewart, args)
stewart
args.type char {mustBeMember(args.type,{'1dof', '2dof', 'flexible'})} = '1dof'
args.k (1,1) double {mustBeNumeric, mustBeNonnegative} = 20e6
args.kp (1,1) double {mustBeNumeric, mustBeNonnegative} = 0
args.ke (1,1) double {mustBeNumeric, mustBeNonnegative} = 5e6
args.ka (1,1) double {mustBeNumeric, mustBeNonnegative} = 60e6
args.c (1,1) double {mustBeNumeric, mustBeNonnegative} = 2e1
args.cp (1,1) double {mustBeNumeric, mustBeNonnegative} = 0
args.ce (1,1) double {mustBeNumeric, mustBeNonnegative} = 1e6
args.ca (1,1) double {mustBeNumeric, mustBeNonnegative} = 10
@ -1873,6 +1958,10 @@ function [stewart] = initializeStrutDynamics(stewart, args)
stewart.actuators.k = args.k;
stewart.actuators.c = args.c;
% Parallel stiffness
stewart.actuators.kp = args.kp;
stewart.actuators.cp = args.cp;
stewart.actuators.ka = args.ka;
stewart.actuators.ca = args.ca;
@ -2530,13 +2619,16 @@ fprintf('ACTUATORS:\n')
if stewart.actuators.type == 1
fprintf('- The actuators are modelled as 1DoF.\n')
fprintf('- The Stiffness and Damping of each actuators is:\n')
fprintf('\t k = %.0e [N/m] \t c = %.0e [N/(m/s)]\n', stewart.actuators.K(1), stewart.actuators.C(1))
fprintf('\t k = %.0e [N/m] \t c = %.0e [N/(m/s)]\n', stewart.actuators.k(1), stewart.actuators.c(1))
if stewart.actuators.kp > 0
fprintf('\t Added parallel stiffness: kp = %.0e [N/m] \t c = %.0e [N/(m/s)]\n', stewart.actuators.kp(1))
end
elseif stewart.actuators.type == 2
fprintf('- The actuators are modelled as 2DoF (APA).\n')
fprintf('- The vertical stiffness and damping contribution of the piezoelectric stack is:\n')
fprintf('\t ka = %.0e [N/m] \t ca = %.0e [N/(m/s)]\n', stewart.actuators.Ka(1), stewart.actuators.Ca(1))
fprintf('\t ka = %.0e [N/m] \t ca = %.0e [N/(m/s)]\n', stewart.actuators.ka(1), stewart.actuators.ca(1))
fprintf('- Vertical stiffness when the piezoelectric stack is removed is:\n')
fprintf('\t kr = %.0e [N/m] \t cr = %.0e [N/(m/s)]\n', stewart.actuators.Kr(1), stewart.actuators.Cr(1))
fprintf('\t kr = %.0e [N/m] \t cr = %.0e [N/(m/s)]\n', stewart.actuators.kr(1), stewart.actuators.cr(1))
elseif stewart.actuators.type == 3
fprintf('- The actuators are modelled with a flexible element (FEM).\n')
end