2020-09-21 13:08:36 +02:00
<?xml version="1.0" encoding="utf-8"?>
< !DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Strict//EN"
"http://www.w3.org/TR/xhtml1/DTD/xhtml1-strict.dtd">
< html xmlns = "http://www.w3.org/1999/xhtml" lang = "en" xml:lang = "en" >
< head >
2021-02-05 16:18:57 +01:00
<!-- 2021 - 02 - 05 ven. 16:05 -->
2020-09-21 13:08:36 +02:00
< meta http-equiv = "Content-Type" content = "text/html;charset=utf-8" / >
2020-11-25 09:40:17 +01:00
< title > Diagonal control using the SVD and the Jacobian Matrix< / title >
2020-09-21 13:08:36 +02:00
< meta name = "generator" content = "Org mode" / >
< meta name = "author" content = "Dehaeze Thomas" / >
2020-11-12 10:18:50 +01:00
< link rel = "stylesheet" type = "text/css" href = "https://research.tdehaeze.xyz/css/style.css" / >
< script type = "text/javascript" src = "https://research.tdehaeze.xyz/js/script.js" > < / script >
2021-01-08 13:58:04 +01:00
< script >
2021-01-11 09:09:48 +01:00
MathJax = {
svg: {
scale: 1,
fontCache: "global"
},
tex: {
tags: "ams",
multlineWidth: "%MULTLINEWIDTH",
tagSide: "right",
macros: {bm: ["\\boldsymbol{#1}",1],},
tagIndent: ".8em"
}
};
< / script >
< script id = "MathJax-script" async
src="https://cdn.jsdelivr.net/npm/mathjax@3/es5/tex-svg.js">< / script >
2020-09-21 13:08:36 +02:00
< / head >
< body >
< div id = "org-div-home-and-up" >
< a accesskey = "h" href = "../index.html" > UP < / a >
|
< a accesskey = "H" href = "../index.html" > HOME < / a >
< / div > < div id = "content" >
2020-11-25 09:40:17 +01:00
< h1 class = "title" > Diagonal control using the SVD and the Jacobian Matrix< / h1 >
2020-09-21 13:08:36 +02:00
< div id = "table-of-contents" >
< h2 > Table of Contents< / h2 >
< div id = "text-table-of-contents" >
< ul >
2021-02-05 16:18:57 +01:00
< li > < a href = "#org8ec288a" > 1. Gravimeter - Simscape Model< / a >
2020-09-21 13:08:36 +02:00
< ul >
2021-02-05 16:18:57 +01:00
< li > < a href = "#orgf4983c2" > 1.1. Introduction< / a > < / li >
< li > < a href = "#orgdabc4d1" > 1.2. Gravimeter Model - Parameters< / a > < / li >
< li > < a href = "#org1c94a53" > 1.3. System Identification< / a > < / li >
< li > < a href = "#org85c666d" > 1.4. Decoupling using the Jacobian< / a > < / li >
< li > < a href = "#orgbc1137a" > 1.5. Decoupling using the SVD< / a > < / li >
< li > < a href = "#org23ddbd2" > 1.6. Verification of the decoupling using the “ Gershgorin Radii” < / a > < / li >
< li > < a href = "#orgd1ccafd" > 1.7. Verification of the decoupling using the “ Relative Gain Array” < / a > < / li >
< li > < a href = "#org7046626" > 1.8. Obtained Decoupled Plants< / a > < / li >
< li > < a href = "#org988560e" > 1.9. Diagonal Controller< / a > < / li >
< li > < a href = "#org9be30dc" > 1.10. Closed-Loop system Performances< / a > < / li >
< li > < a href = "#org722afd8" > 1.11. Robustness to a change of actuator position< / a > < / li >
< li > < a href = "#org4c96e04" > 1.12. Choice of the reference frame for Jacobian decoupling< / a >
2020-12-10 13:16:23 +01:00
< ul >
2021-02-05 16:18:57 +01:00
< li > < a href = "#org9d1ffaa" > 1.12.1. Decoupling of the mass matrix< / a > < / li >
< li > < a href = "#org631cc78" > 1.12.2. Decoupling of the stiffness matrix< / a > < / li >
< li > < a href = "#org542880d" > 1.12.3. Combined decoupling of the mass and stiffness matrices< / a > < / li >
< li > < a href = "#org2620913" > 1.12.4. Conclusion< / a > < / li >
2020-12-10 13:16:23 +01:00
< / ul >
< / li >
2021-02-05 16:18:57 +01:00
< li > < a href = "#org50ced61" > 1.13. SVD decoupling performances< / a > < / li >
2020-09-21 18:03:40 +02:00
< / ul >
< / li >
2021-02-05 16:18:57 +01:00
< li > < a href = "#org355ed58" > 2. Analytical Model< / a >
2020-09-21 18:03:40 +02:00
< ul >
2021-02-05 16:18:57 +01:00
< li > < a href = "#org0e19c48" > 2.1. Model< / a > < / li >
< li > < a href = "#orge18b06d" > 2.2. Stiffness and Mass matrices< / a > < / li >
< li > < a href = "#org2a7d91e" > 2.3. Equations< / a > < / li >
< li > < a href = "#org497ca76" > 2.4. Jacobians< / a > < / li >
< li > < a href = "#org08f124d" > 2.5. Parameters< / a > < / li >
< li > < a href = "#org693f3f2" > 2.6. Transfer function from \(\tau\) to \(\delta \mathcal{L}\)< / a > < / li >
< li > < a href = "#org0643f68" > 2.7. Transfer function from \(\mathcal{F}_{\{M\}}\) to \(\mathcal{X}_{\{M\}}\)< / a > < / li >
< li > < a href = "#org6e35a8e" > 2.8. Transfer function from \(\mathcal{F}_{\{K\}}\) to \(\mathcal{X}_{\{K\}}\)< / a > < / li >
< li > < a href = "#org129b4f5" > 2.9. Analytical< / a >
2021-01-25 11:44:22 +01:00
< ul >
2021-02-05 16:18:57 +01:00
< li > < a href = "#org491abca" > 2.9.1. Parameters< / a > < / li >
2021-01-25 11:44:22 +01:00
< / ul >
< / li >
< / ul >
< / li >
2021-02-05 16:18:57 +01:00
< li > < a href = "#org0554b2d" > 3. Diagonal Stiffness Matrix for a planar manipulator< / a >
2021-01-25 11:44:22 +01:00
< ul >
2021-02-05 16:18:57 +01:00
< li > < a href = "#org6c76761" > 3.1. Model and Assumptions< / a > < / li >
< li > < a href = "#org905b1bd" > 3.2. Objective< / a > < / li >
< li > < a href = "#orge276447" > 3.3. Conditions for Diagonal Stiffness< / a > < / li >
< li > < a href = "#org4806018" > 3.4. Example 1 - Planar manipulator with 3 actuators< / a > < / li >
< li > < a href = "#org6e4302e" > 3.5. Example 2 - Planar manipulator with 4 actuators< / a > < / li >
2021-02-05 13:54:57 +01:00
< / ul >
< / li >
2021-02-05 16:18:57 +01:00
< li > < a href = "#orgae744bc" > 4. Diagonal Stiffness Matrix for a general parallel manipulator< / a >
2021-02-05 13:54:57 +01:00
< ul >
2021-02-05 16:18:57 +01:00
< li > < a href = "#orge5255af" > 4.1. Model and Assumptions< / a > < / li >
< li > < a href = "#orgf0f173d" > 4.2. Objective< / a > < / li >
< li > < a href = "#orgef594c1" > 4.3. Analytical formula of the stiffness matrix< / a > < / li >
< li > < a href = "#org9eb7fb4" > 4.4. Example 1 - 6DoF manipulator (3D)< / a > < / li >
< li > < a href = "#org874d920" > 4.5. Example 2 - Stewart Platform< / a > < / li >
2021-02-05 13:54:57 +01:00
< / ul >
< / li >
2021-02-05 16:18:57 +01:00
< li > < a href = "#orgba9524b" > 5. Stewart Platform - Simscape Model< / a >
2021-02-05 13:54:57 +01:00
< ul >
2021-02-05 16:18:57 +01:00
< li > < a href = "#org80f9d5a" > 5.1. Simscape Model - Parameters< / a > < / li >
< li > < a href = "#org629e737" > 5.2. Identification of the plant< / a > < / li >
< li > < a href = "#org5b2c266" > 5.3. Decoupling using the Jacobian< / a > < / li >
< li > < a href = "#org31c1e90" > 5.4. Decoupling using the SVD< / a > < / li >
< li > < a href = "#org1aa5e5e" > 5.5. Verification of the decoupling using the “ Gershgorin Radii” < / a > < / li >
< li > < a href = "#orgb681966" > 5.6. Verification of the decoupling using the “ Relative Gain Array” < / a > < / li >
< li > < a href = "#org6bea2eb" > 5.7. Obtained Decoupled Plants< / a > < / li >
< li > < a href = "#orga938354" > 5.8. Diagonal Controller< / a > < / li >
< li > < a href = "#org94f7746" > 5.9. Closed-Loop system Performances< / a > < / li >
2020-09-21 13:08:36 +02:00
< / ul >
< / li >
< / ul >
< / div >
< / div >
2021-01-08 13:58:04 +01:00
< hr >
< p > This report is also available as a < a href = "./index.pdf" > pdf< / a > .< / p >
< hr >
2020-09-21 13:08:36 +02:00
2020-11-25 09:40:17 +01:00
< p >
In this document, the use of the Jacobian matrix and the Singular Value Decomposition to render a physical plant diagonal dominant is studied.
Then, a diagonal controller is used.
< / p >
< p >
These two methods are tested on two plants:
< / p >
< ul class = "org-ul" >
2021-02-05 16:18:57 +01:00
< li > In Section < a href = "#orgde5985d" > 1< / a > on a 3-DoF gravimeter< / li >
< li > In Section < a href = "#org98421fb" > 5< / a > on a 6-DoF Stewart platform< / li >
2020-11-25 09:40:17 +01:00
< / ul >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org8ec288a" class = "outline-2" >
< h2 id = "org8ec288a" > < span class = "section-number-2" > 1< / span > Gravimeter - Simscape Model< / h2 >
2020-09-21 13:08:36 +02:00
< div class = "outline-text-2" id = "text-1" >
2020-11-25 09:40:17 +01:00
< p >
2021-02-05 16:18:57 +01:00
< a id = "orgde5985d" > < / a >
2020-11-25 09:40:17 +01:00
< / p >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-orgf4983c2" class = "outline-3" >
< h3 id = "orgf4983c2" > < span class = "section-number-3" > 1.1< / span > Introduction< / h3 >
2020-11-25 09:40:17 +01:00
< div class = "outline-text-3" id = "text-1-1" >
< p >
In this part, diagonal control using both the SVD and the Jacobian matrices are applied on a gravimeter model:
< / p >
< ul class = "org-ul" >
2021-02-05 16:18:57 +01:00
< li > Section < a href = "#orgcca7b2b" > 1.2< / a > : the model is described and its parameters are defined.< / li >
< li > Section < a href = "#org155bb18" > 1.3< / a > : the plant dynamics from the actuators to the sensors is computed from a Simscape model.< / li >
< li > Section < a href = "#orgf5cfec7" > 1.4< / a > : the plant is decoupled using the Jacobian matrices.< / li >
< li > Section < a href = "#org0b56388" > 1.5< / a > : the Singular Value Decomposition is performed on a real approximation of the plant transfer matrix and further use to decouple the system.< / li >
< li > Section < a href = "#org1fdb2f7" > 1.6< / a > : the effectiveness of the decoupling is computed using the Gershorin radii< / li >
< li > Section < a href = "#org1af041a" > 1.7< / a > : the effectiveness of the decoupling is computed using the Relative Gain Array< / li >
< li > Section < a href = "#org84e99a6" > 1.8< / a > : the obtained decoupled plants are compared< / li >
< li > Section < a href = "#org278dee2" > 1.9< / a > : the diagonal controller is developed< / li >
< li > Section < a href = "#org2962140" > 1.10< / a > : the obtained closed-loop performances for the two methods are compared< / li >
< li > Section < a href = "#org28cf806" > 1.11< / a > : the robustness to a change of actuator position is evaluated< / li >
< li > Section < a href = "#orgfe0f8e6" > 1.12< / a > : the choice of the reference frame for the evaluation of the Jacobian is discussed< / li >
< li > Section < a href = "#org7fd82fe" > 1.13< / a > : the decoupling performances of SVD is evaluated for a low damped and an highly damped system< / li >
2020-11-25 09:40:17 +01:00
< / ul >
2020-09-21 13:08:36 +02:00
< / div >
2020-10-05 18:06:49 +02:00
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-orgdabc4d1" class = "outline-3" >
< h3 id = "orgdabc4d1" > < span class = "section-number-3" > 1.2< / span > Gravimeter Model - Parameters< / h3 >
2020-10-05 18:06:49 +02:00
< div class = "outline-text-3" id = "text-1-2" >
2020-11-25 09:40:17 +01:00
< p >
2021-02-05 16:18:57 +01:00
< a id = "orgcca7b2b" > < / a >
2020-11-25 09:40:17 +01:00
< / p >
< p >
2021-02-05 16:18:57 +01:00
The model of the gravimeter is schematically shown in Figure < a href = "#orgcf74ef0" > 1< / a > .
2020-11-25 09:40:17 +01:00
< / p >
2020-09-21 13:08:36 +02:00
2020-11-25 09:17:11 +01:00
2021-02-05 16:18:57 +01:00
< div id = "orgcf74ef0" class = "figure" >
2020-11-25 09:17:11 +01:00
< p > < img src = "figs/gravimeter_model.png" alt = "gravimeter_model.png" / >
< / p >
< p > < span class = "figure-number" > Figure 1: < / span > Model of the gravimeter< / p >
< / div >
2020-12-10 13:16:23 +01:00
2021-02-05 16:18:57 +01:00
< div id = "orga768d5f" class = "figure" >
2020-12-10 13:16:23 +01:00
< p > < img src = "figs/leg_model.png" alt = "leg_model.png" / >
< / p >
< p > < span class = "figure-number" > Figure 2: < / span > Model of the struts< / p >
< / div >
2020-09-30 17:16:30 +02:00
< p >
2020-11-25 09:40:17 +01:00
The parameters used for the simulation are the following:
2020-09-30 17:16:30 +02:00
< / p >
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > l = 1.0; < span class = "org-comment" > % Length of the mass [m]< / span >
h = 1.7; < span class = "org-comment" > % Height of the mass [m]< / span >
2020-09-30 17:16:30 +02:00
2021-01-11 09:09:48 +01:00
la = l< span class = "org-type" > /< / span > 2; < span class = "org-comment" > % Position of Act. [m]< / span >
ha = h< span class = "org-type" > /< / span > 2; < span class = "org-comment" > % Position of Act. [m]< / span >
2020-09-30 17:16:30 +02:00
2021-01-11 09:09:48 +01:00
m = 400; < span class = "org-comment" > % Mass [kg]< / span >
I = 115; < span class = "org-comment" > % Inertia [kg m^2]< / span >
2020-09-30 17:16:30 +02:00
2021-01-11 09:09:48 +01:00
k = 15e3; < span class = "org-comment" > % Actuator Stiffness [N/m]< / span >
c = 2e1; < span class = "org-comment" > % Actuator Damping [N/(m/s)]< / span >
2020-09-30 17:16:30 +02:00
2021-01-11 09:09:48 +01:00
deq = 0.2; < span class = "org-comment" > % Length of the actuators [m]< / span >
2020-09-30 17:16:30 +02:00
2021-01-11 09:09:48 +01:00
g = 0; < span class = "org-comment" > % Gravity [m/s2]< / span >
2020-09-30 17:16:30 +02:00
< / pre >
< / div >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org1c94a53" class = "outline-3" >
< h3 id = "org1c94a53" > < span class = "section-number-3" > 1.3< / span > System Identification< / h3 >
2020-10-05 18:06:49 +02:00
< div class = "outline-text-3" id = "text-1-3" >
2020-11-25 09:40:17 +01:00
< p >
2021-02-05 16:18:57 +01:00
< a id = "org155bb18" > < / a >
2020-11-25 09:40:17 +01:00
< / p >
2020-09-21 13:08:36 +02:00
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > < span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Name of the Simulink File< / span > < / span >
mdl = < span class = "org-string" > 'gravimeter'< / span > ;
< span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Input/Output definition< / span > < / span >
clear io; io_i = 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/F1'< / span > ], 1, < span class = "org-string" > 'openinput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/F2'< / span > ], 1, < span class = "org-string" > 'openinput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/F3'< / span > ], 1, < span class = "org-string" > 'openinput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Acc_side'< / span > ], 1, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Acc_side'< / span > ], 2, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Acc_top'< / span > ], 1, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Acc_top'< / span > ], 2, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
G = linearize(mdl, io);
G.InputName = {< span class = "org-string" > 'F1'< / span > , < span class = "org-string" > 'F2'< / span > , < span class = "org-string" > 'F3'< / span > };
G.OutputName = {< span class = "org-string" > 'Ax1'< / span > , < span class = "org-string" > 'Ay1'< / span > , < span class = "org-string" > 'Ax2'< / span > , < span class = "org-string" > 'Ay2'< / span > };
2020-09-21 13:08:36 +02:00
< / pre >
< / div >
2020-11-16 14:58:26 +01:00
< p >
2021-02-05 16:18:57 +01:00
The inputs and outputs of the plant are shown in Figure < a href = "#org7134a80" > 3< / a > .
2020-11-16 14:58:26 +01:00
< / p >
2020-11-25 09:17:11 +01:00
< p >
More precisely there are three inputs (the three actuator forces):
2020-11-16 14:58:26 +01:00
< / p >
\begin{equation}
2020-11-25 09:17:11 +01:00
\bm{\tau} = \begin{bmatrix}\tau_1 \\ \tau_2 \\ \tau_2 \end{bmatrix}
2020-11-16 14:58:26 +01:00
\end{equation}
2020-11-25 09:17:11 +01:00
< p >
And 4 outputs (the two 2-DoF accelerometers):
< / p >
2020-11-16 14:58:26 +01:00
\begin{equation}
2020-12-10 13:51:57 +01:00
\bm{a} = \begin{bmatrix} a_{1x} \\ a_{1y} \\ a_{2x} \\ a_{2y} \end{bmatrix}
2020-11-16 14:58:26 +01:00
\end{equation}
2020-11-25 09:17:11 +01:00
2021-02-05 16:18:57 +01:00
< div id = "org7134a80" class = "figure" >
2020-11-25 09:17:11 +01:00
< p > < img src = "figs/gravimeter_plant_schematic.png" alt = "gravimeter_plant_schematic.png" / >
< / p >
2020-12-10 13:16:23 +01:00
< p > < span class = "figure-number" > Figure 3: < / span > Schematic of the gravimeter plant< / p >
2020-11-25 09:17:11 +01:00
< / div >
2020-11-16 14:58:26 +01:00
< p >
We can check the poles of the plant:
< / p >
2020-11-25 09:17:11 +01:00
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
2020-11-16 14:58:26 +01:00
2020-11-25 09:17:11 +01:00
< colgroup >
< col class = "org-left" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-left" > -0.12243+13.551i< / td >
< / tr >
< tr >
< td class = "org-left" > -0.12243-13.551i< / td >
< / tr >
< tr >
< td class = "org-left" > -0.05+8.6601i< / td >
< / tr >
< tr >
< td class = "org-left" > -0.05-8.6601i< / td >
< / tr >
< tr >
< td class = "org-left" > -0.0088785+3.6493i< / td >
< / tr >
< tr >
< td class = "org-left" > -0.0088785-3.6493i< / td >
< / tr >
< / tbody >
< / table >
2020-09-30 17:16:30 +02:00
2020-09-21 13:08:36 +02:00
< p >
2020-11-25 09:17:11 +01:00
As expected, the plant as 6 states (2 translations + 1 rotation)
2020-09-21 13:08:36 +02:00
< / p >
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > size(G)
2020-09-21 13:08:36 +02:00
< / pre >
< / div >
< pre class = "example" >
State-space model with 4 outputs, 3 inputs, and 6 states.
< / pre >
2020-11-16 14:58:26 +01:00
< p >
2021-02-05 16:18:57 +01:00
The bode plot of all elements of the plant are shown in Figure < a href = "#org233fce1" > 4< / a > .
2020-11-16 14:58:26 +01:00
< / p >
2020-09-21 13:08:36 +02:00
2021-02-05 16:18:57 +01:00
< div id = "org233fce1" class = "figure" >
2020-09-21 13:08:36 +02:00
< p > < img src = "figs/open_loop_tf.png" alt = "open_loop_tf.png" / >
< / p >
2020-12-10 13:16:23 +01:00
< p > < span class = "figure-number" > Figure 4: < / span > Open Loop Transfer Function from 3 Actuators to 4 Accelerometers< / p >
2020-09-21 13:08:36 +02:00
< / div >
< / div >
< / div >
2020-09-30 17:16:30 +02:00
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org85c666d" class = "outline-3" >
< h3 id = "org85c666d" > < span class = "section-number-3" > 1.4< / span > Decoupling using the Jacobian< / h3 >
2020-10-05 18:06:49 +02:00
< div class = "outline-text-3" id = "text-1-4" >
2020-11-16 14:58:26 +01:00
< p >
2021-02-05 16:18:57 +01:00
< a id = "orgf5cfec7" > < / a >
2020-11-16 14:58:26 +01:00
< / p >
< p >
2021-02-05 16:18:57 +01:00
Consider the control architecture shown in Figure < a href = "#org91fae91" > 5< / a > .
2020-11-16 14:58:26 +01:00
< / p >
< p >
2020-11-25 09:17:11 +01:00
The Jacobian matrix \(J_{\tau}\) is used to transform forces applied by the three actuators into forces/torques applied on the gravimeter at its center of mass:
2020-11-16 14:58:26 +01:00
< / p >
2020-11-25 09:17:11 +01:00
\begin{equation}
2020-12-10 13:51:57 +01:00
\begin{bmatrix} \tau_1 \\ \tau_2 \\ \tau_3 \end{bmatrix} = J_{\tau}^{-T} \begin{bmatrix} F_x \\ F_y \\ M_z \end{bmatrix}
2020-11-25 09:17:11 +01:00
\end{equation}
2020-11-16 14:58:26 +01:00
< p >
2020-11-25 09:17:11 +01:00
The Jacobian matrix \(J_{a}\) is used to compute the vertical acceleration, horizontal acceleration and rotational acceleration of the mass with respect to its center of mass:
< / p >
\begin{equation}
2020-12-10 13:51:57 +01:00
\begin{bmatrix} a_x \\ a_y \\ a_{R_z} \end{bmatrix} = J_{a}^{-1} \begin{bmatrix} a_{x1} \\ a_{y1} \\ a_{x2} \\ a_{y2} \end{bmatrix}
2020-11-25 09:17:11 +01:00
\end{equation}
< p >
2021-02-05 16:18:57 +01:00
We thus define a new plant as defined in Figure < a href = "#org91fae91" > 5< / a > .
2020-11-25 09:17:11 +01:00
\[ \bm{G}_x(s) = J_a^{-1} \bm{G}(s) J_{\tau}^{-T} \]
2020-11-16 14:58:26 +01:00
< / p >
< p >
2021-02-05 16:18:57 +01:00
\(\bm{G}_x(s)\) correspond to the \(3 \times 3\) transfer function matrix from forces and torques applied to the gravimeter at its center of mass to the absolute acceleration of the gravimeter’ s center of mass (Figure < a href = "#org91fae91" > 5< / a > ).
2020-11-16 14:58:26 +01:00
< / p >
2021-02-05 16:18:57 +01:00
< div id = "org91fae91" class = "figure" >
2020-11-16 14:58:26 +01:00
< p > < img src = "figs/gravimeter_decouple_jacobian.png" alt = "gravimeter_decouple_jacobian.png" / >
< / p >
2020-12-10 13:16:23 +01:00
< p > < span class = "figure-number" > Figure 5: < / span > Decoupled plant \(\bm{G}_x\) using the Jacobian matrix \(J\)< / p >
2020-11-16 14:58:26 +01:00
< / div >
< p >
2020-11-25 09:17:11 +01:00
The Jacobian corresponding to the sensors and actuators are defined below:
2020-11-16 14:58:26 +01:00
< / p >
2020-09-30 17:16:30 +02:00
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > Ja = [1 0 < span class = "org-type" > -< / span > h< span class = "org-type" > /< / span > 2
0 1 l< span class = "org-type" > /< / span > 2
1 0 h< span class = "org-type" > /< / span > 2
0 1 0];
Jt = [1 0 < span class = "org-type" > -< / span > ha
0 1 la
0 1 < span class = "org-type" > -< / span > la];
2020-09-30 17:16:30 +02:00
< / pre >
< / div >
2020-11-25 09:17:11 +01:00
< p >
And the plant \(\bm{G}_x\) is computed:
< / p >
2020-09-30 17:16:30 +02:00
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > Gx = pinv(Ja)< span class = "org-type" > *< / span > G< span class = "org-type" > *< / span > pinv(Jt< span class = "org-type" > '< / span > );
Gx.InputName = {< span class = "org-string" > 'Fx'< / span > , < span class = "org-string" > 'Fy'< / span > , < span class = "org-string" > 'Mz'< / span > };
Gx.OutputName = {< span class = "org-string" > 'Dx'< / span > , < span class = "org-string" > 'Dy'< / span > , < span class = "org-string" > 'Rz'< / span > };
2020-09-30 17:16:30 +02:00
< / pre >
< / div >
2020-11-25 09:17:11 +01:00
< pre class = "example" >
size(Gx)
State-space model with 3 outputs, 3 inputs, and 6 states.
< / pre >
2020-09-30 17:16:30 +02:00
< p >
2021-02-05 16:18:57 +01:00
The diagonal and off-diagonal elements of \(G_x\) are shown in Figure < a href = "#orgeb5bc79" > 6< / a > .
2020-09-30 17:16:30 +02:00
< / p >
2021-01-11 09:24:30 +01:00
< p >
It is shown at the system is:
< / p >
< ul class = "org-ul" >
< li > decoupled at high frequency thanks to a diagonal mass matrix (the Jacobian being evaluated at the center of mass of the payload)< / li >
< li > coupled at low frequency due to the non-diagonal terms in the stiffness matrix, especially the term corresponding to a coupling between a force in the x direction to a rotation around z (due to the torque applied by the stiffness 1).< / li >
< / ul >
< p >
2021-02-05 16:18:57 +01:00
The choice of the frame in this the Jacobian is evaluated is discussed in Section < a href = "#orgfe0f8e6" > 1.12< / a > .
2021-01-11 09:24:30 +01:00
< / p >
2020-09-30 17:16:30 +02:00
2021-01-11 09:24:30 +01:00
2021-02-05 16:18:57 +01:00
< div id = "orgeb5bc79" class = "figure" >
2020-11-16 14:58:26 +01:00
< p > < img src = "figs/gravimeter_jacobian_plant.png" alt = "gravimeter_jacobian_plant.png" / >
2020-09-30 17:16:30 +02:00
< / p >
2020-12-10 13:16:23 +01:00
< p > < span class = "figure-number" > Figure 6: < / span > Diagonal and off-diagonal elements of \(G_x\)< / p >
2020-09-30 17:16:30 +02:00
< / div >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-orgbc1137a" class = "outline-3" >
< h3 id = "orgbc1137a" > < span class = "section-number-3" > 1.5< / span > Decoupling using the SVD< / h3 >
2020-10-05 18:06:49 +02:00
< div class = "outline-text-3" id = "text-1-5" >
2020-09-30 17:16:30 +02:00
< p >
2021-02-05 16:18:57 +01:00
< a id = "org0b56388" > < / a >
2020-11-16 14:58:26 +01:00
< / p >
< p >
2020-11-25 09:17:11 +01:00
In order to decouple the plant using the SVD, first a real approximation of the plant transfer function matrix as the crossover frequency is required.
< / p >
< p >
Let’ s compute a real approximation of the complex matrix \(H_1\) which corresponds to the the transfer function \(G(j\omega_c)\) from forces applied by the actuators to the measured acceleration of the top platform evaluated at the frequency \(\omega_c\).
2020-09-30 17:16:30 +02:00
< / p >
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > wc = 2< span class = "org-type" > *< / span > < span class = "org-constant" > pi< / span > < span class = "org-type" > *< / span > 10; < span class = "org-comment" > % Decoupling frequency [rad/s]< / span >
2020-11-16 14:58:26 +01:00
2021-01-11 09:09:48 +01:00
H1 = evalfr(G, < span class = "org-constant" > j< / span > < span class = "org-type" > *< / span > wc);
2020-09-30 17:16:30 +02:00
< / pre >
< / div >
< p >
2020-11-16 14:58:26 +01:00
The real approximation is computed as follows:
2020-09-30 17:16:30 +02:00
< / p >
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > D = pinv(real(H1< span class = "org-type" > '*< / span > H1));
H1 = pinv(D< span class = "org-type" > *< / span > real(H1< span class = "org-type" > '*< / span > diag(exp(< span class = "org-constant" > j< / span > < span class = "org-type" > *< / span > angle(diag(H1< span class = "org-type" > *< / span > D< span class = "org-type" > *< / span > H1< span class = "org-type" > .'< / span > ))< span class = "org-type" > /< / span > 2))));
2020-09-30 17:16:30 +02:00
< / pre >
< / div >
2020-11-16 14:58:26 +01:00
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< caption class = "t-above" > < span class = "table-number" > Table 1:< / span > Real approximate of \(G\) at the decoupling frequency \(\omega_c\)< / caption >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
2020-11-25 09:17:11 +01:00
< td class = "org-right" > 0.0092< / td >
< td class = "org-right" > -0.0039< / td >
< td class = "org-right" > 0.0039< / td >
2020-11-16 14:58:26 +01:00
< / tr >
< tr >
2020-11-25 09:17:11 +01:00
< td class = "org-right" > -0.0039< / td >
< td class = "org-right" > 0.0048< / td >
< td class = "org-right" > 0.00028< / td >
< / tr >
< tr >
< td class = "org-right" > -0.004< / td >
< td class = "org-right" > 0.0038< / td >
< td class = "org-right" > -0.0038< / td >
2020-11-16 14:58:26 +01:00
< / tr >
< tr >
2020-11-25 09:17:11 +01:00
< td class = "org-right" > 8.4e-09< / td >
< td class = "org-right" > 0.0025< / td >
< td class = "org-right" > 0.0025< / td >
2020-11-16 14:58:26 +01:00
< / tr >
< / tbody >
< / table >
2020-09-30 17:16:30 +02:00
2020-10-05 18:28:44 +02:00
< p >
2020-11-25 09:17:11 +01:00
Now, the Singular Value Decomposition of \(H_1\) is performed:
2020-11-16 14:58:26 +01:00
\[ H_1 = U \Sigma V^H \]
2020-10-05 18:28:44 +02:00
< / p >
2020-11-16 14:58:26 +01:00
2020-10-05 18:28:44 +02:00
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > [U,S,V] = svd(H1);
2020-10-05 18:28:44 +02:00
< / pre >
< / div >
2020-12-10 13:16:23 +01:00
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< caption class = "t-above" > < span class = "table-number" > Table 2:< / span > \(U\) matrix< / caption >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > -0.78< / td >
< td class = "org-right" > 0.26< / td >
< td class = "org-right" > -0.53< / td >
< td class = "org-right" > -0.2< / td >
< / tr >
< tr >
< td class = "org-right" > 0.4< / td >
< td class = "org-right" > 0.61< / td >
< td class = "org-right" > -0.04< / td >
< td class = "org-right" > -0.68< / td >
< / tr >
< tr >
< td class = "org-right" > 0.48< / td >
< td class = "org-right" > -0.14< / td >
< td class = "org-right" > -0.85< / td >
< td class = "org-right" > 0.2< / td >
< / tr >
< tr >
< td class = "org-right" > 0.03< / td >
< td class = "org-right" > 0.73< / td >
< td class = "org-right" > 0.06< / td >
< td class = "org-right" > 0.68< / td >
< / tr >
< / tbody >
< / table >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< caption class = "t-above" > < span class = "table-number" > Table 3:< / span > \(V\) matrix< / caption >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > -0.79< / td >
< td class = "org-right" > 0.11< / td >
< td class = "org-right" > -0.6< / td >
< / tr >
< tr >
< td class = "org-right" > 0.51< / td >
< td class = "org-right" > 0.67< / td >
< td class = "org-right" > -0.54< / td >
< / tr >
< tr >
< td class = "org-right" > -0.35< / td >
< td class = "org-right" > 0.73< / td >
< td class = "org-right" > 0.59< / td >
< / tr >
< / tbody >
< / table >
2020-10-05 18:28:44 +02:00
< p >
2021-02-05 16:18:57 +01:00
The obtained matrices \(U\) and \(V\) are used to decouple the system as shown in Figure < a href = "#org27825c4" > 7< / a > .
2020-10-05 18:28:44 +02:00
< / p >
2020-10-05 18:06:49 +02:00
2020-11-16 14:58:26 +01:00
2021-02-05 16:18:57 +01:00
< div id = "org27825c4" class = "figure" >
2020-11-16 14:58:26 +01:00
< p > < img src = "figs/gravimeter_decouple_svd.png" alt = "gravimeter_decouple_svd.png" / >
2020-10-05 18:28:44 +02:00
< / p >
2020-12-10 13:16:23 +01:00
< p > < span class = "figure-number" > Figure 7: < / span > Decoupled plant \(\bm{G}_{SVD}\) using the Singular Value Decomposition< / p >
2020-10-05 18:28:44 +02:00
< / div >
< p >
2020-11-16 14:58:26 +01:00
The decoupled plant is then:
2020-11-25 09:17:11 +01:00
\[ \bm{G}_{SVD}(s) = U^{-1} \bm{G}(s) V^{-H} \]
2020-10-05 18:28:44 +02:00
< / p >
2020-11-16 14:58:26 +01:00
2020-10-05 18:28:44 +02:00
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > Gsvd = inv(U)< span class = "org-type" > *< / span > G< span class = "org-type" > *< / span > inv(V< span class = "org-type" > '< / span > );
2020-10-05 18:28:44 +02:00
< / pre >
< / div >
2020-09-30 17:16:30 +02:00
2020-11-25 09:17:11 +01:00
< pre class = "example" >
size(Gsvd)
State-space model with 4 outputs, 3 inputs, and 6 states.
< / pre >
2020-10-05 18:28:44 +02:00
< p >
2020-11-25 09:17:11 +01:00
The 4th output (corresponding to the null singular value) is discarded, and we only keep the \(3 \times 3\) plant:
2020-10-05 18:28:44 +02:00
< / p >
2020-11-25 09:17:11 +01:00
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > Gsvd = Gsvd(1< span class = "org-type" > :< / span > 3, 1< span class = "org-type" > :< / span > 3);
2020-11-25 09:17:11 +01:00
< / pre >
< / div >
2020-09-30 17:16:30 +02:00
2020-11-25 09:17:11 +01:00
< p >
2021-02-05 16:18:57 +01:00
The diagonal and off-diagonal elements of the “ SVD” plant are shown in Figure < a href = "#org09a3fdf" > 8< / a > .
2020-11-25 09:17:11 +01:00
< / p >
2020-09-30 17:16:30 +02:00
2021-02-05 16:18:57 +01:00
< div id = "org09a3fdf" class = "figure" >
2020-11-16 14:58:26 +01:00
< p > < img src = "figs/gravimeter_svd_plant.png" alt = "gravimeter_svd_plant.png" / >
< / p >
2020-12-10 13:16:23 +01:00
< p > < span class = "figure-number" > Figure 8: < / span > Diagonal and off-diagonal elements of \(G_{svd}\)< / p >
2020-11-16 14:58:26 +01:00
< / div >
< / div >
< / div >
2020-09-30 17:16:30 +02:00
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org23ddbd2" class = "outline-3" >
< h3 id = "org23ddbd2" > < span class = "section-number-3" > 1.6< / span > Verification of the decoupling using the “ Gershgorin Radii” < / h3 >
2020-11-25 09:17:11 +01:00
< div class = "outline-text-3" id = "text-1-6" >
2020-11-16 14:58:26 +01:00
< p >
2021-02-05 16:18:57 +01:00
< a id = "org1fdb2f7" > < / a >
2020-11-16 14:58:26 +01:00
< / p >
2020-09-30 17:16:30 +02:00
2020-11-16 14:58:26 +01:00
< p >
The “ Gershgorin Radii” is computed for the coupled plant \(G(s)\), for the “ Jacobian plant” \(G_x(s)\) and the “ SVD Decoupled Plant” \(G_{SVD}(s)\):
< / p >
2020-09-30 17:16:30 +02:00
2020-10-05 18:28:44 +02:00
< p >
2020-11-16 14:58:26 +01:00
The “ Gershgorin Radii” of a matrix \(S\) is defined by:
\[ \zeta_i(j\omega) = \frac{\sum\limits_{j\neq i}|S_{ij}(j\omega)|}{|S_{ii}(j\omega)|} \]
2020-10-05 18:28:44 +02:00
< / p >
2020-09-30 17:16:30 +02:00
2020-10-05 18:28:44 +02:00
2021-02-05 16:18:57 +01:00
< div id = "orgbc23869" class = "figure" >
2020-11-25 09:17:11 +01:00
< p > < img src = "figs/gravimeter_gershgorin_radii.png" alt = "gravimeter_gershgorin_radii.png" / >
2020-11-16 14:58:26 +01:00
< / p >
2020-12-10 13:16:23 +01:00
< p > < span class = "figure-number" > Figure 9: < / span > Gershgorin Radii of the Coupled and Decoupled plants< / p >
2020-09-30 17:16:30 +02:00
< / div >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-orgd1ccafd" class = "outline-3" >
< h3 id = "orgd1ccafd" > < span class = "section-number-3" > 1.7< / span > Verification of the decoupling using the “ Relative Gain Array” < / h3 >
2020-11-25 09:17:11 +01:00
< div class = "outline-text-3" id = "text-1-7" >
2020-11-16 14:58:26 +01:00
< p >
2021-02-05 16:18:57 +01:00
< a id = "org1af041a" > < / a >
2020-11-16 14:58:26 +01:00
< / p >
2020-09-30 17:16:30 +02:00
2020-11-16 14:58:26 +01:00
< p >
2020-11-25 09:40:17 +01:00
The relative gain array (RGA) is defined as:
< / p >
\begin{equation}
\Lambda\big(G(s)\big) = G(s) \times \big( G(s)^{-1} \big)^T
\end{equation}
< p >
where \(\times\) denotes an element by element multiplication and \(G(s)\) is an \(n \times n\) square transfer matrix.
< / p >
< p >
2021-02-05 16:18:57 +01:00
The obtained RGA elements are shown in Figure < a href = "#org123cc99" > 10< / a > .
2020-11-25 09:40:17 +01:00
< / p >
2021-02-05 16:18:57 +01:00
< div id = "org123cc99" class = "figure" >
2020-11-25 09:40:17 +01:00
< p > < img src = "figs/gravimeter_rga.png" alt = "gravimeter_rga.png" / >
< / p >
2020-12-10 13:16:23 +01:00
< p > < span class = "figure-number" > Figure 10: < / span > Obtained norm of RGA elements for the SVD decoupled plant and the Jacobian decoupled plant< / p >
< / div >
< p >
The RGA-number is also a measure of diagonal dominance:
< / p >
\begin{equation}
\text{RGA-number} = \| \Lambda(G) - I \|_\text{sum}
\end{equation}
2021-02-05 16:18:57 +01:00
< div id = "org24c8fad" class = "figure" >
2020-12-10 13:16:23 +01:00
< p > < img src = "figs/gravimeter_rga_num.png" alt = "gravimeter_rga_num.png" / >
< / p >
< p > < span class = "figure-number" > Figure 11: < / span > RGA-Number for the Gravimeter< / p >
2020-11-25 09:40:17 +01:00
< / div >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org7046626" class = "outline-3" >
< h3 id = "org7046626" > < span class = "section-number-3" > 1.8< / span > Obtained Decoupled Plants< / h3 >
2020-11-25 09:40:17 +01:00
< div class = "outline-text-3" id = "text-1-8" >
< p >
2021-02-05 16:18:57 +01:00
< a id = "org84e99a6" > < / a >
2020-11-25 09:40:17 +01:00
< / p >
< p >
2021-02-05 16:18:57 +01:00
The bode plot of the diagonal and off-diagonal elements of \(G_{SVD}\) are shown in Figure < a href = "#org119a881" > 12< / a > .
2020-09-30 17:16:30 +02:00
< / p >
2021-02-05 16:18:57 +01:00
< div id = "org119a881" class = "figure" >
2020-11-25 09:17:11 +01:00
< p > < img src = "figs/gravimeter_decoupled_plant_svd.png" alt = "gravimeter_decoupled_plant_svd.png" / >
2020-11-16 14:58:26 +01:00
< / p >
2020-12-10 13:16:23 +01:00
< p > < span class = "figure-number" > Figure 12: < / span > Decoupled Plant using SVD< / p >
2020-09-30 17:16:30 +02:00
< / div >
2020-11-16 14:58:26 +01:00
< p >
2021-02-05 16:18:57 +01:00
Similarly, the bode plots of the diagonal elements and off-diagonal elements of the decoupled plant \(G_x(s)\) using the Jacobian are shown in Figure < a href = "#org15a6e3e" > 13< / a > .
2020-11-16 14:58:26 +01:00
< / p >
2020-09-30 17:16:30 +02:00
2021-02-05 16:18:57 +01:00
< div id = "org15a6e3e" class = "figure" >
2020-11-25 09:17:11 +01:00
< p > < img src = "figs/gravimeter_decoupled_plant_jacobian.png" alt = "gravimeter_decoupled_plant_jacobian.png" / >
2020-11-16 14:58:26 +01:00
< / p >
2020-12-10 13:16:23 +01:00
< p > < span class = "figure-number" > Figure 13: < / span > Gravimeter Platform Plant from forces (resp. torques) applied by the legs to the acceleration (resp. angular acceleration) of the platform as well as all the coupling terms between the two (non-diagonal terms of the transfer function matrix)< / p >
2020-09-30 17:16:30 +02:00
< / div >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org988560e" class = "outline-3" >
< h3 id = "org988560e" > < span class = "section-number-3" > 1.9< / span > Diagonal Controller< / h3 >
2020-11-25 09:40:17 +01:00
< div class = "outline-text-3" id = "text-1-9" >
2020-11-16 14:58:26 +01:00
< p >
2021-02-05 16:18:57 +01:00
< a id = "org278dee2" > < / a >
The control diagram for the centralized control is shown in Figure < a href = "#org83797ce" > 14< / a > .
2020-11-16 14:58:26 +01:00
< / p >
2020-09-30 17:16:30 +02:00
2020-11-16 14:58:26 +01:00
< p >
The controller \(K_c\) is “ working” in an cartesian frame.
The Jacobian is used to convert forces in the cartesian frame to forces applied by the actuators.
< / p >
2020-09-30 17:16:30 +02:00
2021-02-05 16:18:57 +01:00
< div id = "org83797ce" class = "figure" >
2020-11-25 09:17:11 +01:00
< p > < img src = "figs/centralized_control_gravimeter.png" alt = "centralized_control_gravimeter.png" / >
2020-11-16 14:58:26 +01:00
< / p >
2020-12-10 13:16:23 +01:00
< p > < span class = "figure-number" > Figure 14: < / span > Control Diagram for the Centralized control< / p >
2020-09-30 17:16:30 +02:00
< / div >
2020-11-16 14:58:26 +01:00
< p >
2021-02-05 16:18:57 +01:00
The SVD control architecture is shown in Figure < a href = "#orge8d9273" > 15< / a > .
2020-11-16 14:58:26 +01:00
The matrices \(U\) and \(V\) are used to decoupled the plant \(G\).
< / p >
2020-09-30 17:16:30 +02:00
2021-02-05 16:18:57 +01:00
< div id = "orge8d9273" class = "figure" >
2020-11-25 09:17:11 +01:00
< p > < img src = "figs/svd_control_gravimeter.png" alt = "svd_control_gravimeter.png" / >
2020-11-16 14:58:26 +01:00
< / p >
2020-12-10 13:16:23 +01:00
< p > < span class = "figure-number" > Figure 15: < / span > Control Diagram for the SVD control< / p >
2020-09-30 17:16:30 +02:00
< / div >
2020-11-16 14:58:26 +01:00
< p >
We choose the controller to be a low pass filter:
\[ K_c(s) = \frac{G_0}{1 + \frac{s}{\omega_0}} \]
< / p >
2020-09-30 17:16:30 +02:00
2020-11-16 14:58:26 +01:00
< p >
\(G_0\) is tuned such that the crossover frequency corresponding to the diagonal terms of the loop gain is equal to \(\omega_c\)
< / p >
2020-09-30 17:16:30 +02:00
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > wc = 2< span class = "org-type" > *< / span > < span class = "org-constant" > pi< / span > < span class = "org-type" > *< / span > 10; < span class = "org-comment" > % Crossover Frequency [rad/s]< / span >
w0 = 2< span class = "org-type" > *< / span > < span class = "org-constant" > pi< / span > < span class = "org-type" > *< / span > 0.1; < span class = "org-comment" > % Controller Pole [rad/s]< / span >
2020-09-30 17:16:30 +02:00
< / pre >
< / div >
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > K_cen = diag(1< span class = "org-type" > ./< / span > diag(abs(evalfr(Gx, < span class = "org-constant" > j< / span > < span class = "org-type" > *< / span > wc))))< span class = "org-type" > *< / span > (1< span class = "org-type" > /< / span > abs(evalfr(1< span class = "org-type" > /< / span > (1 < span class = "org-type" > +< / span > s< span class = "org-type" > /< / span > w0), < span class = "org-constant" > j< / span > < span class = "org-type" > *< / span > wc)))< span class = "org-type" > /< / span > (1 < span class = "org-type" > +< / span > s< span class = "org-type" > /< / span > w0);
L_cen = K_cen< span class = "org-type" > *< / span > Gx;
2020-09-30 17:16:30 +02:00
< / pre >
< / div >
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > K_svd = diag(1< span class = "org-type" > ./< / span > diag(abs(evalfr(Gsvd, < span class = "org-constant" > j< / span > < span class = "org-type" > *< / span > wc))))< span class = "org-type" > *< / span > (1< span class = "org-type" > /< / span > abs(evalfr(1< span class = "org-type" > /< / span > (1 < span class = "org-type" > +< / span > s< span class = "org-type" > /< / span > w0), < span class = "org-constant" > j< / span > < span class = "org-type" > *< / span > wc)))< span class = "org-type" > /< / span > (1 < span class = "org-type" > +< / span > s< span class = "org-type" > /< / span > w0);
L_svd = K_svd< span class = "org-type" > *< / span > Gsvd;
U_inv = inv(U);
2020-09-30 17:16:30 +02:00
< / pre >
< / div >
2020-11-16 14:58:26 +01:00
< p >
2021-02-05 16:18:57 +01:00
The obtained diagonal elements of the loop gains are shown in Figure < a href = "#org1a68d25" > 16< / a > .
2020-11-16 14:58:26 +01:00
< / p >
2021-02-05 16:18:57 +01:00
< div id = "org1a68d25" class = "figure" >
2020-11-16 14:58:26 +01:00
< p > < img src = "figs/gravimeter_comp_loop_gain_diagonal.png" alt = "gravimeter_comp_loop_gain_diagonal.png" / >
< / p >
2020-12-10 13:16:23 +01:00
< p > < span class = "figure-number" > Figure 16: < / span > Comparison of the diagonal elements of the loop gains for the SVD control architecture and the Jacobian one< / p >
2020-09-30 17:16:30 +02:00
< / div >
< / div >
2020-09-21 13:08:36 +02:00
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org9be30dc" class = "outline-3" >
< h3 id = "org9be30dc" > < span class = "section-number-3" > 1.10< / span > Closed-Loop system Performances< / h3 >
2020-11-25 09:40:17 +01:00
< div class = "outline-text-3" id = "text-1-10" >
2020-09-21 13:08:36 +02:00
< p >
2021-02-05 16:18:57 +01:00
< a id = "org2962140" > < / a >
2020-09-30 17:16:30 +02:00
< / p >
2021-01-25 11:44:22 +01:00
< p >
Now the system is identified again with additional inputs and outputs:
< / p >
< ul class = "org-ul" >
< li > \(x\), \(y\) and \(R_z\) ground motion< / li >
< li > \(x\), \(y\) and \(R_z\) acceleration of the payload.< / li >
< / ul >
< div class = "org-src-container" >
< pre class = "src src-matlab" > < span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Name of the Simulink File< / span > < / span >
mdl = < span class = "org-string" > 'gravimeter'< / span > ;
< span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Input/Output definition< / span > < / span >
clear io; io_i = 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Dx'< / span > ], 1, < span class = "org-string" > 'openinput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Dy'< / span > ], 1, < span class = "org-string" > 'openinput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Rz'< / span > ], 1, < span class = "org-string" > 'openinput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/F1'< / span > ], 1, < span class = "org-string" > 'openinput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/F2'< / span > ], 1, < span class = "org-string" > 'openinput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/F3'< / span > ], 1, < span class = "org-string" > 'openinput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Abs_Motion'< / span > ], 1, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Abs_Motion'< / span > ], 2, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Abs_Motion'< / span > ], 3, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Acc_side'< / span > ], 1, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Acc_side'< / span > ], 2, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Acc_top'< / span > ], 1, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Acc_top'< / span > ], 2, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
G = linearize(mdl, io);
G.InputName = {< span class = "org-string" > 'Dx'< / span > , < span class = "org-string" > 'Dy'< / span > , < span class = "org-string" > 'Rz'< / span > , < span class = "org-string" > 'F1'< / span > , < span class = "org-string" > 'F2'< / span > , < span class = "org-string" > 'F3'< / span > };
G.OutputName = {< span class = "org-string" > 'Ax'< / span > , < span class = "org-string" > 'Ay'< / span > , < span class = "org-string" > 'Arz'< / span > , < span class = "org-string" > 'Ax1'< / span > , < span class = "org-string" > 'Ay1'< / span > , < span class = "org-string" > 'Ax2'< / span > , < span class = "org-string" > 'Ay2'< / span > };
< / pre >
< / div >
< p >
The loop is closed using the developed controllers.
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > G_cen = lft(G, < span class = "org-type" > -< / span > pinv(Jt< span class = "org-type" > '< / span > )< span class = "org-type" > *< / span > K_cen< span class = "org-type" > *< / span > pinv(Ja));
G_svd = lft(G, < span class = "org-type" > -< / span > inv(V< span class = "org-type" > '< / span > )< span class = "org-type" > *< / span > K_svd< span class = "org-type" > *< / span > U_inv(1< span class = "org-type" > :< / span > 3, < span class = "org-type" > :< / span > ));
< / pre >
< / div >
2020-09-30 17:16:30 +02:00
< p >
2020-11-16 14:58:26 +01:00
Let’ s first verify the stability of the closed-loop systems:
2020-09-30 17:16:30 +02:00
< / p >
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > isstable(G_cen)
2020-11-16 14:58:26 +01:00
< / pre >
< / div >
2020-09-30 17:16:30 +02:00
2020-11-16 14:58:26 +01:00
< pre class = "example" >
ans =
logical
1
< / pre >
2020-09-30 17:16:30 +02:00
2020-11-16 14:58:26 +01:00
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > isstable(G_svd)
2020-09-30 17:16:30 +02:00
< / pre >
< / div >
2020-11-16 14:58:26 +01:00
< pre class = "example" >
ans =
logical
1
< / pre >
2020-09-30 17:16:30 +02:00
< p >
2021-02-05 16:18:57 +01:00
The obtained transmissibility in Open-loop, for the centralized control as well as for the SVD control are shown in Figure < a href = "#orgeeff325" > 17< / a > .
2020-09-30 17:16:30 +02:00
< / p >
2021-02-05 16:18:57 +01:00
< div id = "orgeeff325" class = "figure" >
2020-11-16 14:58:26 +01:00
< p > < img src = "figs/gravimeter_platform_simscape_cl_transmissibility.png" alt = "gravimeter_platform_simscape_cl_transmissibility.png" / >
< / p >
2020-12-10 13:16:23 +01:00
< p > < span class = "figure-number" > Figure 17: < / span > Obtained Transmissibility< / p >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "org04f6418" class = "figure" >
2020-12-10 13:16:23 +01:00
< p > < img src = "figs/gravimeter_cl_transmissibility_coupling.png" alt = "gravimeter_cl_transmissibility_coupling.png" / >
< / p >
< p > < span class = "figure-number" > Figure 18: < / span > Obtain coupling terms of the transmissibility matrix< / p >
< / div >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org722afd8" class = "outline-3" >
< h3 id = "org722afd8" > < span class = "section-number-3" > 1.11< / span > Robustness to a change of actuator position< / h3 >
2020-12-10 13:16:23 +01:00
< div class = "outline-text-3" id = "text-1-11" >
2021-01-11 09:24:30 +01:00
< p >
2021-02-05 16:18:57 +01:00
< a id = "org28cf806" > < / a >
2021-01-11 09:24:30 +01:00
< / p >
2020-12-10 13:16:23 +01:00
< p >
Let say we change the position of the actuators:
< / p >
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > la = l< span class = "org-type" > /< / span > 2< span class = "org-type" > *< / span > 0.7; < span class = "org-comment" > % Position of Act. [m]< / span >
ha = h< span class = "org-type" > /< / span > 2< span class = "org-type" > *< / span > 0.7; < span class = "org-comment" > % Position of Act. [m]< / span >
2020-12-10 13:16:23 +01:00
< / pre >
< / div >
2021-01-25 11:44:22 +01:00
< div class = "org-src-container" >
< pre class = "src src-matlab" > < span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Name of the Simulink File< / span > < / span >
mdl = < span class = "org-string" > 'gravimeter'< / span > ;
< span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Input/Output definition< / span > < / span >
clear io; io_i = 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Dx'< / span > ], 1, < span class = "org-string" > 'openinput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Dy'< / span > ], 1, < span class = "org-string" > 'openinput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Rz'< / span > ], 1, < span class = "org-string" > 'openinput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/F1'< / span > ], 1, < span class = "org-string" > 'openinput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/F2'< / span > ], 1, < span class = "org-string" > 'openinput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/F3'< / span > ], 1, < span class = "org-string" > 'openinput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Abs_Motion'< / span > ], 1, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Abs_Motion'< / span > ], 2, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Abs_Motion'< / span > ], 3, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Acc_side'< / span > ], 1, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Acc_side'< / span > ], 2, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Acc_top'< / span > ], 1, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Acc_top'< / span > ], 2, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
G = linearize(mdl, io);
G.InputName = {< span class = "org-string" > 'Dx'< / span > , < span class = "org-string" > 'Dy'< / span > , < span class = "org-string" > 'Rz'< / span > , < span class = "org-string" > 'F1'< / span > , < span class = "org-string" > 'F2'< / span > , < span class = "org-string" > 'F3'< / span > };
G.OutputName = {< span class = "org-string" > 'Ax'< / span > , < span class = "org-string" > 'Ay'< / span > , < span class = "org-string" > 'Arz'< / span > , < span class = "org-string" > 'Ax1'< / span > , < span class = "org-string" > 'Ay1'< / span > , < span class = "org-string" > 'Ax2'< / span > , < span class = "org-string" > 'Ay2'< / span > };
< / pre >
< / div >
< p >
The loop is closed using the developed controllers.
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > G_cen_b = lft(G, < span class = "org-type" > -< / span > pinv(Jt< span class = "org-type" > '< / span > )< span class = "org-type" > *< / span > K_cen< span class = "org-type" > *< / span > pinv(Ja));
G_svd_b = lft(G, < span class = "org-type" > -< / span > inv(V< span class = "org-type" > '< / span > )< span class = "org-type" > *< / span > K_svd< span class = "org-type" > *< / span > U_inv(1< span class = "org-type" > :< / span > 3, < span class = "org-type" > :< / span > ));
< / pre >
< / div >
2020-12-10 13:16:23 +01:00
< p >
2021-01-11 09:44:23 +01:00
The new plant is computed, and the centralized and SVD control architectures are applied using the previously computed Jacobian matrices and \(U\) and \(V\) matrices.
2020-12-10 13:16:23 +01:00
< / p >
< p >
2021-02-05 16:18:57 +01:00
The closed-loop system are still stable in both cases, and the obtained transmissibility are equivalent as shown in Figure < a href = "#orga92719f" > 19< / a > .
2020-12-10 13:16:23 +01:00
< / p >
2021-02-05 16:18:57 +01:00
< div id = "orga92719f" class = "figure" >
2020-12-10 13:16:23 +01:00
< p > < img src = "figs/gravimeter_transmissibility_offset_act.png" alt = "gravimeter_transmissibility_offset_act.png" / >
< / p >
< p > < span class = "figure-number" > Figure 19: < / span > Transmissibility for the initial CL system and when the position of actuators are changed< / p >
< / div >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org4c96e04" class = "outline-3" >
< h3 id = "org4c96e04" > < span class = "section-number-3" > 1.12< / span > Choice of the reference frame for Jacobian decoupling< / h3 >
2020-12-10 13:16:23 +01:00
< div class = "outline-text-3" id = "text-1-12" >
< p >
2021-02-05 16:18:57 +01:00
< a id = "orgfe0f8e6" > < / a >
2021-01-11 09:24:30 +01:00
< / p >
< p >
If we want to decouple the system at low frequency (determined by the stiffness matrix), we have to compute the Jacobian at a point where the stiffness matrix is diagonal.
2020-12-10 13:16:23 +01:00
A displacement (resp. rotation) of the mass at this particular point should induce a < b > pure< / b > force (resp. torque) on the same point due to stiffnesses in the system.
This can be verified by geometrical computations.
< / p >
< p >
If we want to decouple the system at high frequency (determined by the mass matrix), we have tot compute the Jacobians at the Center of Mass of the suspended solid.
Similarly to the stiffness analysis, when considering only the inertia effects (neglecting the stiffnesses), a force (resp. torque) applied at this point (the center of mass) should induce a < b > pure< / b > acceleration (resp. angular acceleration).
< / p >
< p >
Ideally, we would like to have a decoupled mass matrix and stiffness matrix at the same time.
To do so, the actuators (springs) should be positioned such that the stiffness matrix is diagonal when evaluated at the CoM of the solid.
< / p >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org9d1ffaa" class = "outline-4" >
< h4 id = "org9d1ffaa" > < span class = "section-number-4" > 1.12.1< / span > Decoupling of the mass matrix< / h4 >
2020-12-10 13:16:23 +01:00
< div class = "outline-text-4" id = "text-1-12-1" >
2021-02-05 16:18:57 +01:00
< div id = "orga5c26a1" class = "figure" >
2020-12-10 13:16:23 +01:00
< p > < img src = "figs/gravimeter_model_M.png" alt = "gravimeter_model_M.png" / >
< / p >
< p > < span class = "figure-number" > Figure 20: < / span > Choice of {O} such that the Mass Matrix is Diagonal< / p >
< / div >
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > la = l< span class = "org-type" > /< / span > 2; < span class = "org-comment" > % Position of Act. [m]< / span >
ha = h< span class = "org-type" > /< / span > 2; < span class = "org-comment" > % Position of Act. [m]< / span >
2020-12-10 13:16:23 +01:00
< / pre >
< / div >
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > < span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Name of the Simulink File< / span > < / span >
mdl = < span class = "org-string" > 'gravimeter'< / span > ;
< span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Input/Output definition< / span > < / span >
clear io; io_i = 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/F1'< / span > ], 1, < span class = "org-string" > 'openinput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/F2'< / span > ], 1, < span class = "org-string" > 'openinput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/F3'< / span > ], 1, < span class = "org-string" > 'openinput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Acc_side'< / span > ], 1, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Acc_side'< / span > ], 2, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Acc_top'< / span > ], 1, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Acc_top'< / span > ], 2, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
G = linearize(mdl, io);
G.InputName = {< span class = "org-string" > 'F1'< / span > , < span class = "org-string" > 'F2'< / span > , < span class = "org-string" > 'F3'< / span > };
G.OutputName = {< span class = "org-string" > 'Ax1'< / span > , < span class = "org-string" > 'Ay1'< / span > , < span class = "org-string" > 'Ax2'< / span > , < span class = "org-string" > 'Ay2'< / span > };
2020-12-10 13:16:23 +01:00
< / pre >
< / div >
< p >
Decoupling at the CoM (Mass decoupled)
< / p >
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > JMa = [1 0 < span class = "org-type" > -< / span > h< span class = "org-type" > /< / span > 2
0 1 l< span class = "org-type" > /< / span > 2
1 0 h< span class = "org-type" > /< / span > 2
0 1 0];
JMt = [1 0 < span class = "org-type" > -< / span > ha
0 1 la
0 1 < span class = "org-type" > -< / span > la];
2020-12-10 13:16:23 +01:00
< / pre >
< / div >
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > GM = pinv(JMa)< span class = "org-type" > *< / span > G< span class = "org-type" > *< / span > pinv(JMt< span class = "org-type" > '< / span > );
GM.InputName = {< span class = "org-string" > 'Fx'< / span > , < span class = "org-string" > 'Fy'< / span > , < span class = "org-string" > 'Mz'< / span > };
GM.OutputName = {< span class = "org-string" > 'Dx'< / span > , < span class = "org-string" > 'Dy'< / span > , < span class = "org-string" > 'Rz'< / span > };
2020-12-10 13:16:23 +01:00
< / pre >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "orgc1c4699" class = "figure" >
2020-12-10 13:16:23 +01:00
< p > < img src = "figs/jac_decoupling_M.png" alt = "jac_decoupling_M.png" / >
< / p >
2020-12-10 13:51:57 +01:00
< p > < span class = "figure-number" > Figure 21: < / span > Diagonal and off-diagonal elements of the decoupled plant< / p >
2020-12-10 13:16:23 +01:00
< / div >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org631cc78" class = "outline-4" >
< h4 id = "org631cc78" > < span class = "section-number-4" > 1.12.2< / span > Decoupling of the stiffness matrix< / h4 >
2020-12-10 13:16:23 +01:00
< div class = "outline-text-4" id = "text-1-12-2" >
2021-02-05 16:18:57 +01:00
< div id = "org4b3e60f" class = "figure" >
2020-12-10 13:16:23 +01:00
< p > < img src = "figs/gravimeter_model_K.png" alt = "gravimeter_model_K.png" / >
< / p >
< p > < span class = "figure-number" > Figure 22: < / span > Choice of {O} such that the Stiffness Matrix is Diagonal< / p >
< / div >
< p >
Decoupling at the point where K is diagonal (x = 0, y = -h/2 from the schematic {O} frame):
< / p >
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > JKa = [1 0 0
0 1 < span class = "org-type" > -< / span > l< span class = "org-type" > /< / span > 2
1 0 < span class = "org-type" > -< / span > h
0 1 0];
JKt = [1 0 0
0 1 < span class = "org-type" > -< / span > la
0 1 la];
2020-12-10 13:16:23 +01:00
< / pre >
< / div >
< p >
And the plant \(\bm{G}_x\) is computed:
< / p >
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > GK = pinv(JKa)< span class = "org-type" > *< / span > G< span class = "org-type" > *< / span > pinv(JKt< span class = "org-type" > '< / span > );
GK.InputName = {< span class = "org-string" > 'Fx'< / span > , < span class = "org-string" > 'Fy'< / span > , < span class = "org-string" > 'Mz'< / span > };
GK.OutputName = {< span class = "org-string" > 'Dx'< / span > , < span class = "org-string" > 'Dy'< / span > , < span class = "org-string" > 'Rz'< / span > };
2020-12-10 13:16:23 +01:00
< / pre >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "org08f9902" class = "figure" >
2020-12-10 13:16:23 +01:00
< p > < img src = "figs/jac_decoupling_K.png" alt = "jac_decoupling_K.png" / >
< / p >
2020-12-10 13:51:57 +01:00
< p > < span class = "figure-number" > Figure 23: < / span > Diagonal and off-diagonal elements of the decoupled plant< / p >
2020-12-10 13:16:23 +01:00
< / div >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org542880d" class = "outline-4" >
< h4 id = "org542880d" > < span class = "section-number-4" > 1.12.3< / span > Combined decoupling of the mass and stiffness matrices< / h4 >
2020-12-10 13:16:23 +01:00
< div class = "outline-text-4" id = "text-1-12-3" >
2021-02-05 16:18:57 +01:00
< div id = "orgc34df19" class = "figure" >
2020-12-10 13:16:23 +01:00
< p > < img src = "figs/gravimeter_model_KM.png" alt = "gravimeter_model_KM.png" / >
< / p >
< p > < span class = "figure-number" > Figure 24: < / span > Ideal location of the actuators such that both the mass and stiffness matrices are diagonal< / p >
< / div >
< p >
To do so, the actuator position should be modified
< / p >
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > la = l< span class = "org-type" > /< / span > 2; < span class = "org-comment" > % Position of Act. [m]< / span >
ha = 0; < span class = "org-comment" > % Position of Act. [m]< / span >
2020-12-10 13:16:23 +01:00
< / pre >
< / div >
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > < span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Name of the Simulink File< / span > < / span >
mdl = < span class = "org-string" > 'gravimeter'< / span > ;
< span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Input/Output definition< / span > < / span >
clear io; io_i = 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/F1'< / span > ], 1, < span class = "org-string" > 'openinput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/F2'< / span > ], 1, < span class = "org-string" > 'openinput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/F3'< / span > ], 1, < span class = "org-string" > 'openinput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Acc_side'< / span > ], 1, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Acc_side'< / span > ], 2, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Acc_top'< / span > ], 1, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Acc_top'< / span > ], 2, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1;
G = linearize(mdl, io);
G.InputName = {< span class = "org-string" > 'F1'< / span > , < span class = "org-string" > 'F2'< / span > , < span class = "org-string" > 'F3'< / span > };
G.OutputName = {< span class = "org-string" > 'Ax1'< / span > , < span class = "org-string" > 'Ay1'< / span > , < span class = "org-string" > 'Ax2'< / span > , < span class = "org-string" > 'Ay2'< / span > };
2020-12-10 13:16:23 +01:00
< / pre >
< / div >
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > JMa = [1 0 < span class = "org-type" > -< / span > h< span class = "org-type" > /< / span > 2
0 1 l< span class = "org-type" > /< / span > 2
1 0 h< span class = "org-type" > /< / span > 2
0 1 0];
JMt = [1 0 < span class = "org-type" > -< / span > ha
0 1 la
0 1 < span class = "org-type" > -< / span > la];
2020-12-10 13:16:23 +01:00
< / pre >
< / div >
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > GKM = pinv(JMa)< span class = "org-type" > *< / span > G< span class = "org-type" > *< / span > pinv(JMt< span class = "org-type" > '< / span > );
GKM.InputName = {< span class = "org-string" > 'Fx'< / span > , < span class = "org-string" > 'Fy'< / span > , < span class = "org-string" > 'Mz'< / span > };
GKM.OutputName = {< span class = "org-string" > 'Dx'< / span > , < span class = "org-string" > 'Dy'< / span > , < span class = "org-string" > 'Rz'< / span > };
2020-12-10 13:16:23 +01:00
< / pre >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "org9d21296" class = "figure" >
2020-12-10 13:16:23 +01:00
< p > < img src = "figs/jac_decoupling_KM.png" alt = "jac_decoupling_KM.png" / >
< / p >
2020-12-10 13:51:57 +01:00
< p > < span class = "figure-number" > Figure 25: < / span > Diagonal and off-diagonal elements of the decoupled plant< / p >
2020-12-10 13:16:23 +01:00
< / div >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org2620913" class = "outline-4" >
< h4 id = "org2620913" > < span class = "section-number-4" > 1.12.4< / span > Conclusion< / h4 >
2020-12-10 13:16:23 +01:00
< div class = "outline-text-4" id = "text-1-12-4" >
< p >
Ideally, the mechanical system should be designed in order to have a decoupled stiffness matrix at the CoM of the solid.
< / p >
< p >
If not the case, the system can either be decoupled as low frequency if the Jacobian are evaluated at a point where the stiffness matrix is decoupled.
Or it can be decoupled at high frequency if the Jacobians are evaluated at the CoM.
< / p >
2020-09-30 17:16:30 +02:00
< / div >
< / div >
< / div >
2020-12-10 13:51:57 +01:00
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org50ced61" class = "outline-3" >
< h3 id = "org50ced61" > < span class = "section-number-3" > 1.13< / span > SVD decoupling performances< / h3 >
2020-12-10 13:51:57 +01:00
< div class = "outline-text-3" id = "text-1-13" >
< p >
2021-02-05 16:18:57 +01:00
< a id = "org7fd82fe" > < / a >
2020-12-10 13:51:57 +01:00
As the SVD is applied on a < b > real approximation< / b > of the plant dynamics at a frequency \(\omega_0\), it is foreseen that the effectiveness of the decoupling depends on the validity of the real approximation.
< / p >
< p >
Let’ s do the SVD decoupling on a plant that is mostly real (low damping) and one with a large imaginary part (larger damping).
< / p >
< p >
2021-02-05 16:18:57 +01:00
Start with small damping, the obtained diagonal and off-diagonal terms are shown in Figure < a href = "#org59af73a" > 26< / a > .
2020-12-10 13:51:57 +01:00
< / p >
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > c = 2e1; < span class = "org-comment" > % Actuator Damping [N/(m/s)]< / span >
2020-12-10 13:51:57 +01:00
< / pre >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "org59af73a" class = "figure" >
2020-12-10 13:51:57 +01:00
< p > < img src = "figs/gravimeter_svd_low_damping.png" alt = "gravimeter_svd_low_damping.png" / >
< / p >
< p > < span class = "figure-number" > Figure 26: < / span > Diagonal and off-diagonal term when decoupling with SVD on the gravimeter with small damping< / p >
< / div >
< p >
2021-02-05 16:18:57 +01:00
Now take a larger damping, the obtained diagonal and off-diagonal terms are shown in Figure < a href = "#orga61723c" > 27< / a > .
2020-12-10 13:51:57 +01:00
< / p >
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > c = 5e2; < span class = "org-comment" > % Actuator Damping [N/(m/s)]< / span >
2020-12-10 13:51:57 +01:00
< / pre >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "orga61723c" class = "figure" >
2020-12-10 13:51:57 +01:00
< p > < img src = "figs/gravimeter_svd_high_damping.png" alt = "gravimeter_svd_high_damping.png" / >
< / p >
< p > < span class = "figure-number" > Figure 27: < / span > Diagonal and off-diagonal term when decoupling with SVD on the gravimeter with high damping< / p >
< / div >
< / div >
< / div >
2020-09-30 17:16:30 +02:00
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org355ed58" class = "outline-2" >
< h2 id = "org355ed58" > < span class = "section-number-2" > 2< / span > Analytical Model< / h2 >
2020-11-16 14:58:26 +01:00
< div class = "outline-text-2" id = "text-2" >
2021-01-25 11:44:22 +01:00
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org0e19c48" class = "outline-3" >
< h3 id = "org0e19c48" > < span class = "section-number-3" > 2.1< / span > Model< / h3 >
2021-01-25 11:44:22 +01:00
< div class = "outline-text-3" id = "text-2-1" >
2021-02-05 16:18:57 +01:00
< div id = "org7f8bb9d" class = "figure" >
2021-01-25 11:44:22 +01:00
< p > < img src = "figs/gravimeter_model_analytical.png" alt = "gravimeter_model_analytical.png" / >
< / p >
< p > < span class = "figure-number" > Figure 28: < / span > Model of the gravimeter< / p >
< / div >
< ul class = "org-ul" >
< li > collocated actuators and sensors< / li >
< / ul >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-orge18b06d" class = "outline-3" >
< h3 id = "orge18b06d" > < span class = "section-number-3" > 2.2< / span > Stiffness and Mass matrices< / h3 >
2021-01-25 11:44:22 +01:00
< div class = "outline-text-3" id = "text-2-2" >
2020-09-30 17:16:30 +02:00
< p >
2021-01-25 11:44:22 +01:00
< b > Stiffness matrix< / b > :
2020-11-25 09:40:17 +01:00
< / p >
2021-01-25 11:44:22 +01:00
\begin{equation}
\mathcal{F}_{\{O\}} = -K_{\{O\}} \mathcal{X}_{\{O\}}
\end{equation}
2020-11-25 09:40:17 +01:00
< p >
2021-01-25 11:44:22 +01:00
with:
< / p >
< ul class = "org-ul" >
< li > \(\mathcal{X}_{\{O\}}\) are displacements/rotations of the mass \(x\), \(y\), \(R_z\) expressed in the frame \(\{O\}\)< / li >
< li > \(\mathcal{F}_{\{O\}}\) are forces/torques \(\mathcal{F}_x\), \(\mathcal{F}_y\), \(\mathcal{M}_z\) applied at the origin of \(\{O\}\)< / li >
< / ul >
< p >
< b > Mass matrix< / b > :
< / p >
\begin{equation}
\mathcal{F}_{\{O\}} = M_{\{O\}} \ddot{\mathcal{X}}_{\{O\}}
\end{equation}
< p >
Consider the two following frames:
< / p >
< ul class = "org-ul" >
< li > \(\{M\}\): Center of mass => diagonal mass matrix
\[ M_{\{M\}} = \begin{bmatrix}m & 0 & 0 \\ 0 & m & 0 \\ 0 & 0 & I\end{bmatrix} \]
\[ K_{\{M\}} = \begin{bmatrix}k_1 & 0 & k_1 h_a \\ 0 & k_2 + k_3 & 0 \\ k_1 h_a & 0 & k_1 h_a + (k_2 + k_3)l_a\end{bmatrix} \]< / li >
< li > \(\{K\}\): Diagonal stiffness matrix
\[ K_{\{K\}} = \begin{bmatrix}k_1 & 0 & 0 \\ 0 & k_2 + k_3 & 0 \\ 0 & 0 & (k_2 + k_3)l_a\end{bmatrix} \]
< ul class = "org-ul" >
< li class = "off" > < code > [  ]< / code > Compute the mass matrix \(M_{\{K\}}\)
Needs two Jacobians => complicated matrix< / li >
< / ul > < / li >
< / ul >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org2a7d91e" class = "outline-3" >
< h3 id = "org2a7d91e" > < span class = "section-number-3" > 2.3< / span > Equations< / h3 >
2021-01-25 11:44:22 +01:00
< div class = "outline-text-3" id = "text-2-3" >
< ul class = "org-ul" >
< li class = "off" > < code > [  ]< / code > Ideally write the equation from \(\tau\) to \(\mathcal{L}\)< / li >
< / ul >
\begin{equation}
\mathcal{L} = \begin{bmatrix} \mathcal{L}_1 \\ \mathcal{L}_2 \\ \mathcal{L}_3 \end{bmatrix}
\end{equation}
\begin{equation}
\tau = \begin{bmatrix} \tau_1 \\ \tau_2 \\ \tau_3 \end{bmatrix}
\end{equation}
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org497ca76" class = "outline-3" >
< h3 id = "org497ca76" > < span class = "section-number-3" > 2.4< / span > Jacobians< / h3 >
2021-01-25 11:44:22 +01:00
< div class = "outline-text-3" id = "text-2-4" >
< p >
Usefulness of Jacobians:
< / p >
< ul class = "org-ul" >
< li > \(J_{\{M\}}\) converts \(\dot{\mathcal{L}}\) to \(\dot{\mathcal{X}}_{\{M\}}\):
\[ \dot{\mathcal{X}}_{\{M\}} = J_{\{M\}} \dot{\mathcal{L}} \]< / li >
< li > \(J_{\{M\}}^T\) converts \(\tau\) to \(\mathcal{F}_{\{M\}}\):
\[ \mathcal{F}_{\{M\}} = J_{\{M\}}^T \tau \]< / li >
< li > \(J_{\{K\}}\) converts $\dot{\mathcal{K}}$to \(\dot{\mathcal{X}}_{\{K\}}\):
\[ \dot{\mathcal{X}}_{\{K\}} = J_{\{K\}} \dot{\mathcal{K}} \]< / li >
< li > \(J_{\{K\}}^T\) converts \(\tau\) to \(\mathcal{F}_{\{K\}}\):
\[ \mathcal{F}_{\{K\}} = J_{\{K\}}^T \tau \]< / li >
< / ul >
< p >
Let’ s compute the Jacobians:
< / p >
\begin{equation}
J_{\{M\}} = \begin{bmatrix} 1 & 0 & h_a \\ 0 & 1 & -l_a \\ 0 & 1 & l_a \end{bmatrix}
\end{equation}
\begin{equation}
J_{\{K\}} = \begin{bmatrix} 1 & 0 & 0 \\ 0 & 1 & -l_a \\ 0 & 1 & l_a \end{bmatrix}
\end{equation}
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org08f124d" class = "outline-3" >
< h3 id = "org08f124d" > < span class = "section-number-3" > 2.5< / span > Parameters< / h3 >
2021-01-25 11:44:22 +01:00
< div class = "outline-text-3" id = "text-2-5" >
< div class = "org-src-container" >
< pre class = "src src-matlab" > l = 1.0; < span class = "org-comment" > % Length of the mass [m]< / span >
h = 2< span class = "org-type" > *< / span > 1.7; < span class = "org-comment" > % Height of the mass [m]< / span >
la = l< span class = "org-type" > /< / span > 2; < span class = "org-comment" > % Position of Act. [m]< / span >
ha = h< span class = "org-type" > /< / span > 2; < span class = "org-comment" > % Position of Act. [m]< / span >
m = 400; < span class = "org-comment" > % Mass [kg]< / span >
I = 115; < span class = "org-comment" > % Inertia [kg m^2]< / span >
c1 = 2e1; < span class = "org-comment" > % Actuator Damping [N/(m/s)]< / span >
c2 = 2e1; < span class = "org-comment" > % Actuator Damping [N/(m/s)]< / span >
c3 = 2e1; < span class = "org-comment" > % Actuator Damping [N/(m/s)]< / span >
k1 = 15e3; < span class = "org-comment" > % Actuator Stiffness [N/m]< / span >
k2 = 15e3; < span class = "org-comment" > % Actuator Stiffness [N/m]< / span >
k3 = 15e3; < span class = "org-comment" > % Actuator Stiffness [N/m]< / span >
< / pre >
< / div >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org693f3f2" class = "outline-3" >
< h3 id = "org693f3f2" > < span class = "section-number-3" > 2.6< / span > Transfer function from \(\tau\) to \(\delta \mathcal{L}\)< / h3 >
2021-01-25 11:44:22 +01:00
< div class = "outline-text-3" id = "text-2-6" >
< p >
Mass, Damping and Stiffness matrices expressed in \(\{M\}\):
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Mm = [m 0 0 ;
0 m 0 ;
0 0 I];
Cm = [c1 0 c1< span class = "org-type" > *< / span > ha ;
0 c2< span class = "org-type" > +< / span > c3 0 ;
c1< span class = "org-type" > *< / span > ha 0 c1< span class = "org-type" > *< / span > ha < span class = "org-type" > +< / span > (c2< span class = "org-type" > +< / span > c3)< span class = "org-type" > *< / span > la];
Km = [k1 0 k1< span class = "org-type" > *< / span > ha ;
0 k2< span class = "org-type" > +< / span > k3 0 ;
k1< span class = "org-type" > *< / span > ha 0 k1< span class = "org-type" > *< / span > ha < span class = "org-type" > +< / span > (k2< span class = "org-type" > +< / span > k3)< span class = "org-type" > *< / span > la];
< / pre >
< / div >
< p >
Jacobian \(J_{\{M\}}\):
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Jm = [1 0 ha ;
0 1 < span class = "org-type" > -< / span > la ;
0 1 la];
< / pre >
< / div >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Mt = inv(Jm< span class = "org-type" > '< / span > )< span class = "org-type" > *< / span > Mm< span class = "org-type" > *< / span > inv(Jm);
Ct = inv(Jm< span class = "org-type" > '< / span > )< span class = "org-type" > *< / span > Cm< span class = "org-type" > *< / span > inv(Jm);
Kt = inv(Jm< span class = "org-type" > '< / span > )< span class = "org-type" > *< / span > Km< span class = "org-type" > *< / span > inv(Jm);
< / pre >
< / div >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< caption class = "t-above" > < span class = "table-number" > Table 4:< / span > \(M_t\)< / caption >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 400.0< / td >
< td class = "org-right" > 340.0< / td >
< td class = "org-right" > -340.0< / td >
< / tr >
< tr >
< td class = "org-right" > 340.0< / td >
< td class = "org-right" > 504.0< / td >
< td class = "org-right" > -304.0< / td >
< / tr >
< tr >
< td class = "org-right" > -340.0< / td >
< td class = "org-right" > -304.0< / td >
< td class = "org-right" > 504.0< / td >
< / tr >
< / tbody >
< / table >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< caption class = "t-above" > < span class = "table-number" > Table 5:< / span > \(K_t\)< / caption >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 15000.0< / td >
< td class = "org-right" > 0.0< / td >
< td class = "org-right" > 0.0< / td >
< / tr >
< tr >
< td class = "org-right" > 0.0< / td >
< td class = "org-right" > 24412.5< / td >
< td class = "org-right" > -9412.5< / td >
< / tr >
< tr >
< td class = "org-right" > 0.0< / td >
< td class = "org-right" > -9412.5< / td >
< td class = "org-right" > 24412.5< / td >
< / tr >
< / tbody >
< / table >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Gt = s< span class = "org-type" > ^< / span > 2< span class = "org-type" > *< / span > inv(Mt< span class = "org-type" > *< / span > s< span class = "org-type" > ^< / span > 2 < span class = "org-type" > +< / span > Ct< span class = "org-type" > *< / span > s < span class = "org-type" > +< / span > Kt);
< span class = "org-comment" > % Gt = JM*s^2*inv(MM*s^2 + CM*s + KM)*JM';< / span >
< / pre >
< / div >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org0643f68" class = "outline-3" >
< h3 id = "org0643f68" > < span class = "section-number-3" > 2.7< / span > Transfer function from \(\mathcal{F}_{\{M\}}\) to \(\mathcal{X}_{\{M\}}\)< / h3 >
2021-01-25 11:44:22 +01:00
< div class = "outline-text-3" id = "text-2-7" >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Gm = inv(Jm)< span class = "org-type" > *< / span > Gt< span class = "org-type" > *< / span > inv(Jm< span class = "org-type" > '< / span > );
< / pre >
< / div >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< caption class = "t-above" > < span class = "table-number" > Table 6:< / span > \(M_{\{M\}}\)< / caption >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 400.0< / td >
< td class = "org-right" > 0.0< / td >
< td class = "org-right" > 0.0< / td >
< / tr >
< tr >
< td class = "org-right" > 0.0< / td >
< td class = "org-right" > 400.0< / td >
< td class = "org-right" > 0.0< / td >
< / tr >
< tr >
< td class = "org-right" > 0.0< / td >
< td class = "org-right" > 0.0< / td >
< td class = "org-right" > 115.0< / td >
< / tr >
< / tbody >
< / table >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< caption class = "t-above" > < span class = "table-number" > Table 7:< / span > \(K_{\{M\}}\)< / caption >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 15000.0< / td >
< td class = "org-right" > 0.0< / td >
< td class = "org-right" > 12750.0< / td >
< / tr >
< tr >
< td class = "org-right" > 0.0< / td >
< td class = "org-right" > 30000.0< / td >
< td class = "org-right" > 0.0< / td >
< / tr >
< tr >
< td class = "org-right" > 12750.0< / td >
< td class = "org-right" > 0.0< / td >
< td class = "org-right" > 27750.0< / td >
< / tr >
< / tbody >
< / table >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org6e35a8e" class = "outline-3" >
< h3 id = "org6e35a8e" > < span class = "section-number-3" > 2.8< / span > Transfer function from \(\mathcal{F}_{\{K\}}\) to \(\mathcal{X}_{\{K\}}\)< / h3 >
2021-01-25 11:44:22 +01:00
< div class = "outline-text-3" id = "text-2-8" >
< p >
Jacobian:
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Jk = [1 0 0
0 1 < span class = "org-type" > -< / span > la
0 1 la];
< / pre >
< / div >
< p >
Mass, Damping and Stiffness matrices expressed in \(\{K\}\):
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Mk = Jk< span class = "org-type" > '*< / span > Mt< span class = "org-type" > *< / span > Jk;
Ck = Jk< span class = "org-type" > '*< / span > Ct< span class = "org-type" > *< / span > Jk;
Kk = Jk< span class = "org-type" > '*< / span > Kt< span class = "org-type" > *< / span > Jk;
< / pre >
< / div >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< caption class = "t-above" > < span class = "table-number" > Table 8:< / span > \(M_{\{K\}}\)< / caption >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 400.0< / td >
< td class = "org-right" > 0.0< / td >
< td class = "org-right" > -340.0< / td >
< / tr >
< tr >
< td class = "org-right" > 0.0< / td >
< td class = "org-right" > 400.0< / td >
< td class = "org-right" > 0.0< / td >
< / tr >
< tr >
< td class = "org-right" > -340.0< / td >
< td class = "org-right" > 0.0< / td >
< td class = "org-right" > 404.0< / td >
< / tr >
< / tbody >
< / table >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< caption class = "t-above" > < span class = "table-number" > Table 9:< / span > \(K_{\{K\}}\)< / caption >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 15000.0< / td >
< td class = "org-right" > 0.0< / td >
< td class = "org-right" > 0.0< / td >
< / tr >
< tr >
< td class = "org-right" > 0.0< / td >
< td class = "org-right" > 30000.0< / td >
< td class = "org-right" > 0.0< / td >
< / tr >
< tr >
< td class = "org-right" > 0.0< / td >
< td class = "org-right" > 0.0< / td >
< td class = "org-right" > 16912.5< / td >
< / tr >
< / tbody >
< / table >
< div class = "org-src-container" >
< pre class = "src src-matlab" > < span class = "org-comment" > % Gk = s^2*inv(Mk*s^2 + Ck*s + Kk);< / span >
Gk = inv(Jk)< span class = "org-type" > *< / span > Gt< span class = "org-type" > *< / span > inv(Jk< span class = "org-type" > '< / span > );
< / pre >
< / div >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org129b4f5" class = "outline-3" >
< h3 id = "org129b4f5" > < span class = "section-number-3" > 2.9< / span > Analytical< / h3 >
2021-01-25 11:44:22 +01:00
< div class = "outline-text-3" id = "text-2-9" >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org491abca" class = "outline-4" >
< h4 id = "org491abca" > < span class = "section-number-4" > 2.9.1< / span > Parameters< / h4 >
2021-01-25 11:44:22 +01:00
< div class = "outline-text-4" id = "text-2-9-1" >
< div class = "org-src-container" >
< pre class = "src src-matlab" > syms la ha m I c k positive
< / pre >
< / div >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Mm = [m 0 0 ;
0 m 0 ;
0 0 I];
Cm = [c 0 c< span class = "org-type" > *< / span > ha ;
0 2< span class = "org-type" > *< / span > c 0 ;
c< span class = "org-type" > *< / span > ha 0 c< span class = "org-type" > *< / span > (ha< span class = "org-type" > +< / span > 2< span class = "org-type" > *< / span > la)];
Km = [k 0 k< span class = "org-type" > *< / span > ha ;
0 2< span class = "org-type" > *< / span > k 0 ;
k< span class = "org-type" > *< / span > ha 0 k< span class = "org-type" > *< / span > (ha< span class = "org-type" > +< / span > 2< span class = "org-type" > *< / span > la)];
< / pre >
< / div >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Jm = [1 0 ha ;
0 1 < span class = "org-type" > -< / span > la ;
0 1 la];
< / pre >
< / div >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Mt = inv(Jm< span class = "org-type" > '< / span > )< span class = "org-type" > *< / span > Mm< span class = "org-type" > *< / span > inv(Jm);
Ct = inv(Jm< span class = "org-type" > '< / span > )< span class = "org-type" > *< / span > Cm< span class = "org-type" > *< / span > inv(Jm);
Kt = inv(Jm< span class = "org-type" > '< / span > )< span class = "org-type" > *< / span > Km< span class = "org-type" > *< / span > inv(Jm);
< / pre >
< / div >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Jk = [1 0 0
0 1 < span class = "org-type" > -< / span > la
0 1 la];
< / pre >
< / div >
< p >
Mass, Damping and Stiffness matrices expressed in \(\{K\}\):
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Mk = Jk< span class = "org-type" > '*< / span > Mt< span class = "org-type" > *< / span > Jk;
Ck = Jk< span class = "org-type" > '*< / span > Ct< span class = "org-type" > *< / span > Jk;
Kk = Jk< span class = "org-type" > '*< / span > Kt< span class = "org-type" > *< / span > Jk;
< / pre >
< / div >
< div class = "org-src-container" >
< pre class = "src src-matlab" > [< span class = "org-string" > '\begin{equation} M_{\{K\}} = '< / span > , latex(simplify(Kk)), < span class = "org-string" > '\end{equation}'< / span > ]
< / pre >
< / div >
\begin{equation} M_{\{K\}} = \left(\begin{array}{ccc} k & 0 & 0\\ 0 & 2\,k & 0\\ 0 & 0 & k\,\left(-{\mathrm{ha}}^2+\mathrm{ha}+2\,\mathrm{la}\right) \end{array}\right)\end{equation}
< / div >
< / div >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org0554b2d" class = "outline-2" >
< h2 id = "org0554b2d" > < span class = "section-number-2" > 3< / span > Diagonal Stiffness Matrix for a planar manipulator< / h2 >
2021-01-25 11:44:22 +01:00
< div class = "outline-text-2" id = "text-3" >
2021-02-05 13:54:57 +01:00
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org6c76761" class = "outline-3" >
< h3 id = "org6c76761" > < span class = "section-number-3" > 3.1< / span > Model and Assumptions< / h3 >
2021-02-05 13:54:57 +01:00
< div class = "outline-text-3" id = "text-3-1" >
2021-01-25 11:44:22 +01:00
< p >
2021-02-05 13:54:57 +01:00
Consider a parallel manipulator with:
2020-11-06 16:59:03 +01:00
< / p >
< ul class = "org-ul" >
2021-02-05 13:54:57 +01:00
< li > \(b_i\): location of the joints on the top platform are called \(b_i\)< / li >
< li > \(\hat{s}_i\): unit vector corresponding to the struts< / li >
< li > \(k_i\): stiffness of the struts< / li >
< li > \(\tau_i\): actuator forces< / li >
< li > \(O_M\): center of mass of the solid body< / li >
2020-11-06 16:59:03 +01:00
< / ul >
2020-11-06 11:59:09 +01:00
< p >
2021-02-05 13:54:57 +01:00
Consider two frames:
2020-11-06 11:59:09 +01:00
< / p >
< ul class = "org-ul" >
2021-02-05 13:54:57 +01:00
< li > \(\{M\}\) with origin \(O_M\)< / li >
< li > \(\{K\}\) with origin \(O_K\)< / li >
2020-11-06 11:59:09 +01:00
< / ul >
2020-11-25 09:40:17 +01:00
2020-11-06 11:59:09 +01:00
< p >
2021-02-05 16:18:57 +01:00
As an example, take the system shown in Figure < a href = "#orgb43395b" > 29< / a > .
2020-11-06 11:59:09 +01:00
< / p >
2020-09-21 13:08:36 +02:00
2021-02-05 16:18:57 +01:00
< div id = "orgb43395b" class = "figure" >
2021-02-05 13:54:57 +01:00
< p > < img src = "figs/3dof_model_fully_parallel.png" alt = "3dof_model_fully_parallel.png" / >
< / p >
< p > < span class = "figure-number" > Figure 29: < / span > Example of 3DoF parallel platform< / p >
< / div >
< / div >
2020-09-21 13:08:36 +02:00
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org905b1bd" class = "outline-3" >
< h3 id = "org905b1bd" > < span class = "section-number-3" > 3.2< / span > Objective< / h3 >
2021-02-05 13:54:57 +01:00
< div class = "outline-text-3" id = "text-3-2" >
2020-11-23 18:01:13 +01:00
< p >
2021-02-05 13:54:57 +01:00
The objective is to find conditions for the existence of a frame \(\{K\}\) in which the Stiffness matrix of the manipulator is diagonal.
If the conditions are fulfilled, a second objective is to fine the location of the frame \(\{K\}\) analytically.
2020-11-23 18:01:13 +01:00
< / p >
2021-02-05 13:54:57 +01:00
< / div >
2020-11-23 18:01:13 +01:00
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-orge276447" class = "outline-3" >
< h3 id = "orge276447" > < span class = "section-number-3" > 3.3< / span > Conditions for Diagonal Stiffness< / h3 >
2021-02-05 13:54:57 +01:00
< div class = "outline-text-3" id = "text-3-3" >
2020-09-21 13:08:36 +02:00
< p >
2021-02-05 13:54:57 +01:00
The stiffness matrix in the frame \(\{K\}\) can be expressed as:
2020-11-06 11:59:09 +01:00
< / p >
2021-02-05 13:54:57 +01:00
\begin{equation} \label{eq:stiffness_formula_planar}
K_{\{K\}} = J_{\{K\}}^T \mathcal{K} J_{\{K\}}
\end{equation}
2020-11-06 11:59:09 +01:00
< p >
2021-02-05 13:54:57 +01:00
where:
2020-09-21 13:08:36 +02:00
< / p >
2021-02-05 13:54:57 +01:00
< ul class = "org-ul" >
< li > \(J_{\{K\}}\) is the Jacobian transformation from the struts to the frame \(\{K\}\)< / li >
2021-02-05 15:45:49 +01:00
< li > < p >
\(\mathcal{K}\) is a diagonal matrix with the strut stiffnesses on the diagonal
< / p >
\begin{equation}
\mathcal{K} = \begin{bmatrix}
k_1 & & & 0 \\
& k_2 & & \\
& & \ddots & \\
0 & & & k_n
\end{bmatrix}
\end{equation}< / li >
2021-02-05 13:54:57 +01:00
< / ul >
2020-11-06 15:06:25 +01:00
< p >
2021-02-05 13:54:57 +01:00
The Jacobian for a planar manipulator, evaluated in a frame \(\{K\}\), can be expressed as follows:
2020-11-06 15:06:25 +01:00
< / p >
2021-02-05 13:54:57 +01:00
\begin{equation} \label{eq:jacobian_planar}
J_{\{K\}} = \begin{bmatrix}
{}^K\hat{s}_1^T & {}^Kb_{1,x} {}^K\hat{s}_{1,y} - {}^Kb_{1,x} {}^K\hat{s}_{1,y} \\
{}^K\hat{s}_2^T & {}^Kb_{2,x} {}^K\hat{s}_{2,y} - {}^Kb_{2,x} {}^K\hat{s}_{2,y} \\
\vdots & \vdots \\
{}^K\hat{s}_n^T & {}^Kb_{n,x} {}^K\hat{s}_{n,y} - {}^Kb_{n,x} {}^K\hat{s}_{n,y} \\
\end{bmatrix}
\end{equation}
2020-11-06 17:02:58 +01:00
2021-02-05 13:54:57 +01:00
< p >
Let’ s omit the mention of frame, it is assumed that vectors are expressed in frame \(\{K\}\).
It is specified otherwise.
2020-11-06 17:02:58 +01:00
< / p >
2021-02-05 13:54:57 +01:00
< p >
Injecting \eqref{eq:jacobian_planar} into \eqref{eq:stiffness_formula_planar} yields:
2020-11-06 17:02:58 +01:00
< / p >
2021-02-05 13:54:57 +01:00
\begin{equation}
\boxed{
K_{\{K\}} = \left[ \begin{array}{c|c}
k_i \hat{s}_i \hat{s}_i^T & k_i \hat{s}_i (b_{i,x}\hat{s}_{i,y} - b_{i,y}\hat{s}_{i,x}) \cr
\hline
k_i \hat{s}_i (b_{i,x}\hat{s}_{i,y} - b_{i,y}\hat{s}_{i,x}) & k_i (b_{i,x}\hat{s}_{i,y} - b_{i,y}\hat{s}_{i,x})^2
\end{array} \right]
}
\end{equation}
2020-09-21 13:08:36 +02:00
2020-11-06 11:59:09 +01:00
< p >
2021-02-05 13:54:57 +01:00
In order to have a decoupled stiffness matrix, we have the following two conditions:
2020-11-06 16:59:03 +01:00
< / p >
2021-02-05 13:54:57 +01:00
\begin{align}
k_i \hat{s}_i \hat{s}_i^T & = \text{diag. matrix} \label{eq:diag_cond_2D_1} \\
k_i \hat{s}_i (b_{i,x}\hat{s}_{i,y} - b_{i,y}\hat{s}_{i,x}) & = 0 \label{eq:diag_cond_2D_2}
\end{align}
2020-11-06 16:59:03 +01:00
< p >
2021-02-05 13:54:57 +01:00
Note that we don’ t have any condition on the term \(k_i (b_{i,x}\hat{s}_{i,y} - b_{i,y}\hat{s}_{i,x})^2\) as it is only a scalar.
2020-11-06 16:59:03 +01:00
< / p >
< p >
2021-02-05 13:54:57 +01:00
Condition \eqref{eq:diag_cond_2D_1}:
2020-11-06 11:59:09 +01:00
< / p >
2020-11-06 16:59:03 +01:00
< ul class = "org-ul" >
2021-02-05 13:54:57 +01:00
< li > represents the coupling between translations and forces< / li >
< li > does only depends on the orientation of the struts and the stiffnesses and not on the choice of frame< / li >
< li > it is therefore a intrinsic property of the chosen geometry< / li >
2020-11-06 16:59:03 +01:00
< / ul >
2020-11-06 11:59:09 +01:00
2020-09-21 13:08:36 +02:00
< p >
2021-02-05 13:54:57 +01:00
Condition \eqref{eq:diag_cond_2D_2}:
2020-09-21 13:08:36 +02:00
< / p >
2021-02-05 13:54:57 +01:00
< ul class = "org-ul" >
< li > represents the coupling between forces/rotations and torques/translation< / li >
< li > it does depend on the positions of the joints \(b_i\) in the frame \(\{K\}\)< / li >
< / ul >
2020-11-06 16:59:03 +01:00
2021-02-05 13:54:57 +01:00
< p >
Let’ s make a change of frame from the initial frame \(\{M\}\) to the frame \(\{K\}\):
2020-11-06 16:59:03 +01:00
< / p >
2021-02-05 13:54:57 +01:00
\begin{align}
{}^Kb_i & = {}^Mb_i - {}^MO_K \\
{}^K\hat{s}_i & = {}^M\hat{s}_i
\end{align}
2021-01-11 09:09:48 +01:00
2021-02-05 13:54:57 +01:00
< p >
And the goal is to find \({}^MO_K\) such that \eqref{eq:diag_cond_2D_2} is fulfilled:
< / p >
\begin{equation}
k_i ({}^Mb_{i,x}\hat{s}_{i,y} - {}^Mb_{i,y}\hat{s}_{i,x} - {}^MO_{K,x}\hat{s}_{i,y} + {}^MO_{K,y}\hat{s}_{i,x}) \hat{s}_i = 0
\end{equation}
\begin{equation}
k_i ({}^Mb_{i,x}\hat{s}_{i,y} - {}^Mb_{i,y}\hat{s}_{i,x}) \hat{s}_i = {}^MO_{K,x} k_i \hat{s}_{i,y} \hat{s}_i - {}^MO_{K,y} k_i \hat{s}_{i,x} \hat{s}_i
\end{equation}
2020-09-21 13:08:36 +02:00
2020-09-21 18:03:40 +02:00
< p >
2021-02-05 13:54:57 +01:00
And we have two sets of linear equations of two unknowns.
2020-09-21 18:03:40 +02:00
< / p >
2020-09-21 13:14:25 +02:00
2021-02-05 13:54:57 +01:00
< p >
This can be easily solved by writing the equations in a matrix form:
< / p >
\begin{equation}
\underbrace{k_i ({}^Mb_{i,x}\hat{s}_{i,y} - {}^Mb_{i,y}\hat{s}_{i,x}) \hat{s}_i}_{2 \times 1} =
\underbrace{\begin{bmatrix}
& \\
k_i \hat{s}_{i,y} \hat{s}_i & - k_i \hat{s}_{i,x} \hat{s}_i \\
& \\
\end{bmatrix}}_{2 \times 2}
\underbrace{\begin{bmatrix}
{}^MO_{K,x}\\
{}^MO_{K,y}
\end{bmatrix}}_{2 \times 1}
\end{equation}
2020-09-21 13:14:25 +02:00
2021-02-05 13:54:57 +01:00
< p >
And finally, if the matrix is invertible:
< / p >
\begin{equation}
\boxed{
{}^MO_K = {\begin{bmatrix}
& \\
k_i \hat{s}_{i,y} \hat{s}_i & - k_i \hat{s}_{i,x} \hat{s}_i \\
& \\
\end{bmatrix}}^{-1} k_i ({}^Mb_{i,x}\hat{s}_{i,y} - {}^Mb_{i,y}\hat{s}_{i,x}) \hat{s}_i
}
\end{equation}
2020-09-21 13:14:25 +02:00
2020-11-06 11:59:09 +01:00
< p >
2021-02-05 13:54:57 +01:00
Note that a rotation of the frame \(\{K\}\) with respect to frame \(\{M\}\) would make not change on the “ diagonality” of \(K_{\{K\}}\).
2020-11-06 11:59:09 +01:00
< / p >
2021-02-05 13:54:57 +01:00
< / div >
< / div >
2020-11-06 11:59:09 +01:00
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org4806018" class = "outline-3" >
< h3 id = "org4806018" > < span class = "section-number-3" > 3.4< / span > Example 1 - Planar manipulator with 3 actuators< / h3 >
2021-02-05 13:54:57 +01:00
< div class = "outline-text-3" id = "text-3-4" >
2020-11-06 16:59:03 +01:00
< p >
2021-02-05 16:18:57 +01:00
Consider system of Figure < a href = "#orgec9f5fd" > 30< / a > .
2020-11-06 11:59:09 +01:00
< / p >
2020-09-21 18:03:40 +02:00
2020-11-06 16:59:03 +01:00
2021-02-05 16:18:57 +01:00
< div id = "orgec9f5fd" class = "figure" >
2021-02-05 13:54:57 +01:00
< p > < img src = "figs/3dof_model_fully_parallel.png" alt = "3dof_model_fully_parallel.png" / >
2020-09-21 13:08:36 +02:00
< / p >
2021-02-05 13:54:57 +01:00
< p > < span class = "figure-number" > Figure 30: < / span > Example of 3DoF parallel platform< / p >
2020-09-21 18:03:40 +02:00
< / div >
2020-09-21 13:08:36 +02:00
2020-11-06 11:59:09 +01:00
< p >
2021-02-05 13:54:57 +01:00
The stiffnesses \(k_i\), the joint positions \({}^Mb_i\) and joint unit vectors \({}^M\hat{s}_i\) are defined below:
2020-11-06 11:59:09 +01:00
< / p >
2021-02-05 13:54:57 +01:00
< div class = "org-src-container" >
< pre class = "src src-matlab" > ki = [5,1,2]; < span class = "org-comment" > % Stiffnesses [N/m]< / span >
si = [[1;0],[0;1],[0;1]]; si = si< span class = "org-type" > ./< / span > vecnorm(si); < span class = "org-comment" > % Unit Vectors< / span >
bi = [[< span class = "org-type" > -< / span > 1;0.5],[< span class = "org-type" > -< / span > 2;< span class = "org-type" > -< / span > 1],[0;< span class = "org-type" > -< / span > 1]]; < span class = "org-comment" > % Joint's positions in frame {M}< / span >
< / pre >
< / div >
2020-09-21 13:08:36 +02:00
2020-11-23 18:01:13 +01:00
< p >
2021-02-05 13:58:54 +01:00
Let’ s first verify that condition \eqref{eq:diag_cond_2D_1} is true:
2020-11-23 18:01:13 +01:00
< / p >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
2021-02-05 13:54:57 +01:00
< colgroup >
2020-11-23 18:01:13 +01:00
< col class = "org-right" / >
2020-11-06 11:59:09 +01:00
2020-11-23 18:01:13 +01:00
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
2021-02-05 13:54:57 +01:00
< td class = "org-right" > 5< / td >
< td class = "org-right" > 0< / td >
2020-11-23 18:01:13 +01:00
< / tr >
< tr >
2021-02-05 13:54:57 +01:00
< td class = "org-right" > 0< / td >
< td class = "org-right" > 2< / td >
2020-11-23 18:01:13 +01:00
< / tr >
< / tbody >
< / table >
2021-02-05 13:54:57 +01:00
< p >
Now, compute \({}^MO_K\):
2020-09-21 13:08:36 +02:00
< / p >
2021-02-05 13:54:57 +01:00
< div class = "org-src-container" >
< pre class = "src src-matlab" > Ok = inv([sum(ki< span class = "org-type" > .*< / span > si(2,< span class = "org-type" > :< / span > )< span class = "org-type" > .*< / span > si, 2), < span class = "org-type" > -< / span > sum(ki< span class = "org-type" > .*< / span > si(1,< span class = "org-type" > :< / span > )< span class = "org-type" > .*< / span > si, 2)])< span class = "org-type" > *< / span > sum(ki< span class = "org-type" > .*< / span > (bi(1,< span class = "org-type" > :< / span > )< span class = "org-type" > .*< / span > si(2,< span class = "org-type" > :< / span > ) < span class = "org-type" > -< / span > bi(2,< span class = "org-type" > :< / span > )< span class = "org-type" > .*< / span > si(1,< span class = "org-type" > :< / span > ))< span class = "org-type" > .*< / span > si, 2);
< / pre >
2020-09-21 13:08:36 +02:00
< / div >
2021-02-05 16:18:57 +01:00
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< colgroup >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > -1< / td >
< / tr >
< tr >
< td class = "org-right" > 0.5< / td >
< / tr >
< / tbody >
< / table >
2020-11-06 16:59:03 +01:00
< p >
2021-02-05 13:54:57 +01:00
Let’ s compute the new coordinates \({}^Kb_i\) after the change of frame:
2020-11-06 16:59:03 +01:00
< / p >
2021-02-05 13:54:57 +01:00
< div class = "org-src-container" >
< pre class = "src src-matlab" > Kbi = bi < span class = "org-type" > -< / span > Ok;
< / pre >
< / div >
2020-09-21 13:08:36 +02:00
2020-11-06 16:59:03 +01:00
< p >
2021-02-05 13:54:57 +01:00
In order to verify that the new frame \(\{K\}\) indeed yields a diagonal stiffness matrix, we first compute the Jacobian \(J_{\{K\}}\):
2020-09-21 13:08:36 +02:00
< / p >
2021-02-05 13:54:57 +01:00
< div class = "org-src-container" >
< pre class = "src src-matlab" > Jk = [si< span class = "org-type" > '< / span > , (Kbi(1,< span class = "org-type" > :< / span > )< span class = "org-type" > .*< / span > si(2,< span class = "org-type" > :< / span > ) < span class = "org-type" > -< / span > Kbi(2,< span class = "org-type" > :< / span > )< span class = "org-type" > .*< / span > si(1,< span class = "org-type" > :< / span > ))< span class = "org-type" > '< / span > ];
< / pre >
< / div >
2020-11-06 16:59:03 +01:00
2021-02-05 16:18:57 +01:00
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 1< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< / tr >
< tr >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 1< / td >
< td class = "org-right" > -1< / td >
< / tr >
< tr >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 1< / td >
< td class = "org-right" > 1< / td >
< / tr >
< / tbody >
< / table >
2021-02-05 13:54:57 +01:00
< p >
And the stiffness matrix:
< / p >
2020-11-06 16:59:03 +01:00
< div class = "org-src-container" >
2021-02-05 13:54:57 +01:00
< pre class = "src src-matlab" > K = Jk< span class = "org-type" > '*< / span > diag(ki)< span class = "org-type" > *< / span > Jk
2020-11-06 16:59:03 +01:00
< / pre >
2020-11-06 11:59:09 +01:00
< / div >
2021-02-05 16:18:57 +01:00
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 5< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< / tr >
< tr >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 2< / td >
< td class = "org-right" > 0< / td >
< / tr >
< tr >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 2< / td >
< / tr >
< / tbody >
< / table >
2020-09-21 13:08:36 +02:00
< / div >
< / div >
2020-09-21 18:03:40 +02:00
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org6e4302e" class = "outline-3" >
< h3 id = "org6e4302e" > < span class = "section-number-3" > 3.5< / span > Example 2 - Planar manipulator with 4 actuators< / h3 >
2021-02-05 13:54:57 +01:00
< div class = "outline-text-3" id = "text-3-5" >
2020-11-06 11:59:09 +01:00
< p >
2021-02-05 16:18:57 +01:00
Now consider the planar manipulator of Figure < a href = "#org53f3954" > 31< / a > .
2020-11-25 09:40:17 +01:00
< / p >
2021-02-05 13:54:57 +01:00
2021-02-05 16:18:57 +01:00
< div id = "org53f3954" class = "figure" >
2021-02-05 13:54:57 +01:00
< p > < img src = "figs/model_planar_2.png" alt = "model_planar_2.png" / >
2020-09-21 18:03:40 +02:00
< / p >
2021-02-05 13:54:57 +01:00
< p > < span class = "figure-number" > Figure 31: < / span > Planar Manipulator< / p >
< / div >
2020-09-21 18:03:40 +02:00
< p >
2021-02-05 13:54:57 +01:00
The stiffnesses \(k_i\), the joint positions \({}^Mb_i\) and joint unit vectors \({}^M\hat{s}_i\) are defined below:
2020-09-21 18:03:40 +02:00
< / p >
< div class = "org-src-container" >
2021-02-05 13:54:57 +01:00
< pre class = "src src-matlab" > ki = [1,2,1,1];
si = [[1;0],[0;1],[< span class = "org-type" > -< / span > 1;0],[0;1]];
si = si< span class = "org-type" > ./< / span > vecnorm(si);
h = 0.2;
L = 2;
bi = [[< span class = "org-type" > -< / span > L< span class = "org-type" > /< / span > 2;h],[< span class = "org-type" > -< / span > L< span class = "org-type" > /< / span > 2;< span class = "org-type" > -< / span > h],[L< span class = "org-type" > /< / span > 2;h],[L< span class = "org-type" > /< / span > 2;h]];
2020-09-21 18:03:40 +02:00
< / pre >
< / div >
< p >
2021-02-05 13:58:54 +01:00
Let’ s first verify that condition \eqref{eq:diag_cond_2D_1} is true:
2020-09-21 18:03:40 +02:00
< / p >
< div class = "org-src-container" >
2021-02-05 13:54:57 +01:00
< pre class = "src src-matlab" > ki< span class = "org-type" > .*< / span > si< span class = "org-type" > *< / span > si< span class = "org-type" > '< / span >
2020-09-21 18:03:40 +02:00
< / pre >
< / div >
2020-11-06 11:59:09 +01:00
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
2021-02-05 13:54:57 +01:00
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 2< / td >
< td class = "org-right" > 0< / td >
< / tr >
< tr >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 3< / td >
< / tr >
< / tbody >
< / table >
< p >
Now, compute \({}^MO_K\):
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Ok = inv([sum(ki< span class = "org-type" > .*< / span > si(2,< span class = "org-type" > :< / span > )< span class = "org-type" > .*< / span > si, 2), < span class = "org-type" > -< / span > sum(ki< span class = "org-type" > .*< / span > si(1,< span class = "org-type" > :< / span > )< span class = "org-type" > .*< / span > si, 2)])< span class = "org-type" > *< / span > sum(ki< span class = "org-type" > .*< / span > (bi(1,< span class = "org-type" > :< / span > )< span class = "org-type" > .*< / span > si(2,< span class = "org-type" > :< / span > ) < span class = "org-type" > -< / span > bi(2,< span class = "org-type" > :< / span > )< span class = "org-type" > .*< / span > si(1,< span class = "org-type" > :< / span > ))< span class = "org-type" > .*< / span > si, 2);
< / pre >
< / div >
2021-02-05 16:18:57 +01:00
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< colgroup >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > -0.33333< / td >
< / tr >
< tr >
< td class = "org-right" > 0.2< / td >
< / tr >
< / tbody >
< / table >
2021-02-05 13:54:57 +01:00
< p >
Let’ s compute the new coordinates \({}^Kb_i\) after the change of frame:
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Kbi = bi < span class = "org-type" > -< / span > Ok;
< / pre >
< / div >
< p >
In order to verify that the new frame \(\{K\}\) indeed yields a diagonal stiffness matrix, we first compute the Jacobian \(J_{\{K\}}\):
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Jk = [si< span class = "org-type" > '< / span > , (Kbi(1,< span class = "org-type" > :< / span > )< span class = "org-type" > .*< / span > si(2,< span class = "org-type" > :< / span > ) < span class = "org-type" > -< / span > Kbi(2,< span class = "org-type" > :< / span > )< span class = "org-type" > .*< / span > si(1,< span class = "org-type" > :< / span > ))< span class = "org-type" > '< / span > ];
< / pre >
< / div >
2021-02-05 16:18:57 +01:00
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 1< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< / tr >
< tr >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 1< / td >
< td class = "org-right" > -0.66667< / td >
< / tr >
< tr >
< td class = "org-right" > -1< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< / tr >
< tr >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 1< / td >
< td class = "org-right" > 1.3333< / td >
< / tr >
< / tbody >
< / table >
2021-02-05 13:54:57 +01:00
< p >
And the stiffness matrix:
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > K = Jk< span class = "org-type" > '*< / span > diag(ki)< span class = "org-type" > *< / span > Jk
< / pre >
< / div >
2021-02-05 16:18:57 +01:00
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 2< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< / tr >
< tr >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 3< / td >
< td class = "org-right" > -2.2204e-16< / td >
< / tr >
< tr >
< td class = "org-right" > 0< / td >
< td class = "org-right" > -2.2204e-16< / td >
< td class = "org-right" > 2.6667< / td >
< / tr >
< / tbody >
< / table >
2021-02-05 13:54:57 +01:00
< / div >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-orgae744bc" class = "outline-2" >
< h2 id = "orgae744bc" > < span class = "section-number-2" > 4< / span > Diagonal Stiffness Matrix for a general parallel manipulator< / h2 >
2021-02-05 13:54:57 +01:00
< div class = "outline-text-2" id = "text-4" >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-orge5255af" class = "outline-3" >
< h3 id = "orge5255af" > < span class = "section-number-3" > 4.1< / span > Model and Assumptions< / h3 >
2021-02-05 13:54:57 +01:00
< div class = "outline-text-3" id = "text-4-1" >
< p >
Let’ s consider a 6dof parallel manipulator with:
< / p >
< ul class = "org-ul" >
< li > \(b_i\): location of the joints on the top platform are called \(b_i\)< / li >
< li > \(\hat{s}_i\): unit vector corresponding to the struts< / li >
< li > \(k_i\): stiffness of the struts< / li >
< li > \(\tau_i\): actuator forces< / li >
< li > \(O_M\): center of mass of the solid body< / li >
< / ul >
< p >
Consider two frames:
< / p >
< ul class = "org-ul" >
< li > \(\{M\}\) with origin \(O_M\)< / li >
< li > \(\{K\}\) with origin \(O_K\)< / li >
< / ul >
< p >
2021-02-05 16:18:57 +01:00
An example is shown in Figure < a href = "#orgc4158cb" > 32< / a > .
2021-02-05 13:54:57 +01:00
< / p >
2021-02-05 16:18:57 +01:00
< div id = "orgc4158cb" class = "figure" >
2021-02-05 13:54:57 +01:00
< p > < img src = "figs/stewart_architecture_example.png" alt = "stewart_architecture_example.png" / >
< / p >
< p > < span class = "figure-number" > Figure 32: < / span > Parallel manipulator Example< / p >
< / div >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-orgf0f173d" class = "outline-3" >
< h3 id = "orgf0f173d" > < span class = "section-number-3" > 4.2< / span > Objective< / h3 >
2021-02-05 13:54:57 +01:00
< div class = "outline-text-3" id = "text-4-2" >
< p >
The objective is to find conditions for the existence of a frame \(\{K\}\) in which the Stiffness matrix of the manipulator is diagonal.
If the conditions are fulfilled, a second objective is to fine the location of the frame \(\{K\}\) analytically.
< / p >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-orgef594c1" class = "outline-3" >
< h3 id = "orgef594c1" > < span class = "section-number-3" > 4.3< / span > Analytical formula of the stiffness matrix< / h3 >
2021-02-05 13:54:57 +01:00
< div class = "outline-text-3" id = "text-4-3" >
< p >
For a fully parallel manipulator, the stiffness matrix \(K_{\{K\}}\) expressed in a frame \(\{K\}\) is:
< / p >
\begin{equation}
K_{\{K\}} = J_{\{K\}}^T \mathcal{K} J_{\{K\}}
\end{equation}
< p >
where:
< / p >
< ul class = "org-ul" >
2021-02-05 15:45:49 +01:00
< li > \(J_{\{K\}}\) is the Jacobian transformation from the struts to the frame \(\{K\}\)< / li >
< li > < p >
\(\mathcal{K}\) is a diagonal matrix with the strut stiffnesses on the diagonal:
< / p >
\begin{equation}
\mathcal{K} = \begin{bmatrix}
k_1 & & & 0 \\
& k_2 & & \\
& & \ddots & \\
0 & & & k_n
\end{bmatrix}
\end{equation}< / li >
2021-02-05 13:54:57 +01:00
< / ul >
2021-02-05 15:45:49 +01:00
2021-02-05 13:54:57 +01:00
< p >
The analytical expression of \(J_{\{K\}}\) is:
< / p >
\begin{equation}
J_{\{K\}} = \begin{bmatrix}
{}^K\hat{s}_1^T & ({}^Kb_1 \times {}^K\hat{s}_1)^T \\
{}^K\hat{s}_2^T & ({}^Kb_2 \times {}^K\hat{s}_2)^T \\
\vdots & \vdots \\
{}^K\hat{s}_n^T & ({}^Kb_n \times {}^K\hat{s}_n)^T
\end{bmatrix}
\end{equation}
< p >
To simplify, we ignore the superscript \(K\) and we assume that all vectors / positions are expressed in this frame \(\{K\}\).
Otherwise, it is explicitly written.
< / p >
< p >
Let’ s now write the analytical expressing of the stiffness matrix \(K_{\{K\}}\):
< / p >
\begin{equation}
K_{\{K\}} = \begin{bmatrix}
\hat{s}_1 & \dots & \hat{s}_n \\
(b_1 \times \hat{s}_1) & \dots & (b_n \times \hat{s}_n)
\end{bmatrix}
\begin{bmatrix}
k_1 & & \\
& \ddots & \\
& & k_n
\end{bmatrix}
\begin{bmatrix}
\hat{s}_1^T & (b_1 \times \hat{s}_1)^T \\
\hat{s}_2^T & (b_2 \times \hat{s}_2)^T \\
\vdots & \dots \\
\hat{s}_n^T & (b_n \times \hat{s}_n)^T
\end{bmatrix}
\end{equation}
< p >
And we finally obtain:
< / p >
\begin{equation}
\boxed{
K_{\{K\}} = \left[ \begin{array}{c|c}
k_i \hat{s}_i \hat{s}_i^T & k_i \hat{s}_i (b_i \times \hat{s}_i)^T \cr
\hline
k_i \hat{s}_i (b_i \times \hat{s}_i)^T & k_i (b_i \times \hat{s}_i) (b_i \times \hat{s}_i)^T
\end{array} \right]
}
\end{equation}
< p >
We want the stiffness matrix to be diagonal, therefore, we have the following conditions:
< / p >
\begin{align}
k_i \hat{s}_i \hat{s}_i^T & = \text{diag. matrix} \label{eq:diag_cond_1} \\
k_i (b_i \times \hat{s}_i) (b_i \times \hat{s}_i)^T & = \text{diag. matrix} \label{eq:diag_cond_2} \\
k_i \hat{s}_i (b_i \times \hat{s}_i)^T & = 0 \label{eq:diag_cond_3}
\end{align}
< p >
Note that:
< / p >
< ul class = "org-ul" >
< li > condition \eqref{eq:diag_cond_1} corresponds to coupling between forces applied on \(O_K\) to translations of the payload.
It does not depend on the choice of \(\{K\}\), it only depends on the orientation of the struts and the stiffnesses.
It is therefore an intrinsic property of the manipulator.< / li >
< li > condition \eqref{eq:diag_cond_2} corresponds to the coupling between forces applied on \(O_K\) and rotation of the payload.
Similarly, it does also correspond to the coupling between torques applied on \(O_K\) to translations of the payload.< / li >
< li > condition \eqref{eq:diag_cond_3} corresponds to the coupling between torques applied on \(O_K\) to rotation of the payload.< / li >
< li > conditions \eqref{eq:diag_cond_2} and \eqref{eq:diag_cond_3} do depend on the positions \({}^Kb_i\) and therefore depend on the choice of \(\{K\}\).< / li >
< / ul >
< p >
Note that if we find a frame \(\{K\}\) in which the stiffness matrix \(K_{\{K\}}\) is diagonal, it will still be diagonal for any rotation of the frame \(\{K\}\).
Therefore, we here suppose that the frame \(\{K\}\) is aligned with the initial frame \(\{M\}\).
< / p >
< p >
Let’ s make a change of frame from the initial frame \(\{M\}\) to the frame \(\{K\}\):
< / p >
\begin{align}
{}^Kb_i & = {}^Mb_i - {}^MO_K \\
{}^K\hat{s}_i & = {}^M\hat{s}_i
\end{align}
< p >
The goal is to find \({}^MO_K\) such that conditions \eqref{eq:diag_cond_2} and \eqref{eq:diag_cond_3} are fulfilled.
< / p >
< p >
Let’ s first solve equation \eqref{eq:diag_cond_3} that corresponds to the coupling between forces and rotations:
< / p >
\begin{equation}
k_i \hat{s}_i (({}^Mb_i - {}^MO_K) \times \hat{s}_i)^T = 0
\end{equation}
< p >
Taking the transpose and re-arranging:
< / p >
\begin{equation}
k_i ({}^Mb_i \times \hat{s}_i) \hat{s}_i^T = k_i ({}^MO_K \times \hat{s}_i) \hat{s}_i^T
\end{equation}
< p >
2021-02-05 15:45:49 +01:00
As the vector cross product also can be expressed as the product of a skew-symmetric matrix and a vehttps://rwth.zoom.us/j/92311133102?pwd=UTAzS21YYkUwT2pMZDBLazlGNzdvdz09tor, we obtain:
2021-02-05 13:54:57 +01:00
< / p >
\begin{equation}
k_i ({}^Mb_i \times \hat{s}_i) \hat{s}_i^T = {}^M\bm{O}_{K} ( k_i \hat{s}_i \hat{s}_i^T )
\end{equation}
< p >
with:
< / p >
\begin{equation} \label{eq:skew_symmetric_cross_product}
{}^M\bm{O}_K = \begin{bmatrix}
0 & -{}^MO_{K,z} & {}^MO_{K,y} \\
{}^MO_{K,z} & 0 & -{}^MO_{K,x} \\
-{}^MO_{K,y} & {}^MO_{K,x} & 0
\end{bmatrix}
\end{equation}
< p >
We suppose \(k_i \hat{s}_i \hat{s}_i^T\) invertible as it is diagonal from \eqref{eq:diag_cond_1}.
< / p >
< p >
And finally, we find:
< / p >
\begin{equation}
\boxed{
{}^M\bm{O}_{K} = \left( k_i ({}^Mb_i \times \hat{s}_i) \hat{s}_i^T\right) \cdot {\left( k_i \hat{s}_i \hat{s}_i^T \right)}^{-1}
}
\end{equation}
< p >
If the obtained \({}^M\bm{O}_{K}\) is a skew-symmetric matrix, we can easily determine the corresponding vector \({}^MO_K\) from \eqref{eq:skew_symmetric_cross_product}.
< / p >
< p >
In such case, condition \eqref{eq:diag_cond_2} is fulfilled and there is no coupling between translations and rotations in the frame \(\{K\}\).
< / p >
< p >
Then, we can only verify if condition \eqref{eq:diag_cond_3} is verified or not.
< / p >
2021-02-05 16:18:57 +01:00
< div class = "note" id = "org94b74f1" >
2021-02-05 13:54:57 +01:00
< p >
If there is no frame \(\{K\}\) such that conditions \eqref{eq:diag_cond_2} and \eqref{eq:diag_cond_3} are valid, it would be interesting to be able to determine the frame \(\{K\}\) in which is coupling is minimal.
< / p >
< / div >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org9eb7fb4" class = "outline-3" >
< h3 id = "org9eb7fb4" > < span class = "section-number-3" > 4.4< / span > Example 1 - 6DoF manipulator (3D)< / h3 >
2021-02-05 13:54:57 +01:00
< div class = "outline-text-3" id = "text-4-4" >
< p >
Let’ s define the geometry of the manipulator (\({}^Mb_i\), \({}^Ms_i\) and \(k_i\)):
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > ki = [2,2,1,1,3,3,1,1,1,1,2,2];
si = [[< span class = "org-type" > -< / span > 1;0;0],[< span class = "org-type" > -< / span > 1;0;0],[< span class = "org-type" > -< / span > 1;0;0],[< span class = "org-type" > -< / span > 1;0;0],[0;0;1],[0;0;1],[0;0;1],[0;0;1],[0;< span class = "org-type" > -< / span > 1;0],[0;< span class = "org-type" > -< / span > 1;0],[0;< span class = "org-type" > -< / span > 1;0],[0;< span class = "org-type" > -< / span > 1;0]];
bi = [[1;< span class = "org-type" > -< / span > 1;1],[1;1;< span class = "org-type" > -< / span > 1],[1;1;1],[1;< span class = "org-type" > -< / span > 1;< span class = "org-type" > -< / span > 1],[1;< span class = "org-type" > -< / span > 1;< span class = "org-type" > -< / span > 1],[< span class = "org-type" > -< / span > 1;1;< span class = "org-type" > -< / span > 1],[1;1;< span class = "org-type" > -< / span > 1],[< span class = "org-type" > -< / span > 1;< span class = "org-type" > -< / span > 1;< span class = "org-type" > -< / span > 1],[1;1;< span class = "org-type" > -< / span > 1],[< span class = "org-type" > -< / span > 1;1;1],[< span class = "org-type" > -< / span > 1;1;< span class = "org-type" > -< / span > 1],[1;1;1]]< span class = "org-type" > -< / span > [0;2;< span class = "org-type" > -< / span > 1];
< / pre >
< / div >
< p >
Cond 1:
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > ki< span class = "org-type" > .*< / span > si< span class = "org-type" > *< / span > si< span class = "org-type" > '< / span >
< / pre >
< / div >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 6< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< / tr >
< tr >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 6< / td >
< td class = "org-right" > 0< / td >
< / tr >
< tr >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 8< / td >
< / tr >
< / tbody >
< / table >
< p >
Find Ok
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > OkX = (ki< span class = "org-type" > .*< / span > cross(bi, si)< span class = "org-type" > *< / span > si< span class = "org-type" > '< / span > )< span class = "org-type" > /< / span > (ki< span class = "org-type" > .*< / span > si< span class = "org-type" > *< / span > si< span class = "org-type" > '< / span > );
< span class = "org-keyword" > if< / span > all(diag(OkX) < span class = "org-type" > ==< / span > 0) < span class = "org-type" > & & < / span > all(all((OkX < span class = "org-type" > +< / span > OkX< span class = "org-type" > '< / span > ) < span class = "org-type" > ==< / span > 0))
disp(< span class = "org-string" > 'OkX is skew symmetric'< / span > )
Ok = [OkX(3,2);OkX(1,3);OkX(2,1)]
< span class = "org-keyword" > else< / span >
error(< span class = "org-string" > 'OkX is *not* skew symmetric'< / span > )
< span class = "org-keyword" > end< / span >
< / pre >
< / div >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< colgroup >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 0< / td >
< / tr >
< tr >
< td class = "org-right" > -2< / td >
< / tr >
< tr >
< td class = "org-right" > 1< / td >
< / tr >
< / tbody >
< / table >
< div class = "org-src-container" >
< pre class = "src src-matlab" > < span class = "org-comment" > % Verification of second condition< / span >
si< span class = "org-type" > *< / span > cross(bi< span class = "org-type" > -< / span > Ok, si)< span class = "org-type" > '< / span >
< / pre >
< / div >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< / tr >
< tr >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< / tr >
< tr >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< / tr >
< / tbody >
< / table >
< p >
Verification of third condition
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > ki< span class = "org-type" > .*< / span > cross(bi< span class = "org-type" > -< / span > Ok, si)< span class = "org-type" > *< / span > cross(bi< span class = "org-type" > -< / span > Ok, si)< span class = "org-type" > '< / span >
< / pre >
< / div >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 14< / td >
< td class = "org-right" > 4< / td >
< td class = "org-right" > -2< / td >
< / tr >
< tr >
< td class = "org-right" > 4< / td >
< td class = "org-right" > 14< / td >
< td class = "org-right" > 2< / td >
< / tr >
< tr >
< td class = "org-right" > -2< / td >
< td class = "org-right" > 2< / td >
< td class = "org-right" > 12< / td >
< / tr >
< / tbody >
< / table >
< p >
Let’ s compute the Jacobian:
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Jk = [si< span class = "org-type" > '< / span > , cross(bi < span class = "org-type" > -< / span > Ok, si)< span class = "org-type" > '< / span > ];
< / pre >
< / div >
< p >
And the stiffness matrix:
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Jk< span class = "org-type" > '*< / span > diag(ki)< span class = "org-type" > *< / span > Jk
< / pre >
< / div >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 6< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< / tr >
< tr >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 6< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< / tr >
< tr >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 8< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< / tr >
< tr >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 14< / td >
< td class = "org-right" > 4< / td >
< td class = "org-right" > -2< / td >
< / tr >
< tr >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 4< / td >
< td class = "org-right" > 14< / td >
< td class = "org-right" > 2< / td >
< / tr >
< tr >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > -2< / td >
< td class = "org-right" > 2< / td >
< td class = "org-right" > 12< / td >
< / tr >
< / tbody >
< / table >
< div class = "org-src-container" >
< pre class = "src src-matlab" > < span class = "org-type" > figure< / span > ;
hold on;
< span class = "org-type" > set< / span > (< span class = "org-variable-name" > gca< / span > ,< span class = "org-string" > 'ColorOrderIndex'< / span > ,1)
plot(b1(1), b1(2), < span class = "org-string" > 'o'< / span > );
< span class = "org-type" > set< / span > (< span class = "org-variable-name" > gca< / span > ,< span class = "org-string" > 'ColorOrderIndex'< / span > ,2)
plot(b2(1), b2(2), < span class = "org-string" > 'o'< / span > );
< span class = "org-type" > set< / span > (< span class = "org-variable-name" > gca< / span > ,< span class = "org-string" > 'ColorOrderIndex'< / span > ,3)
plot(b3(1), b3(2), < span class = "org-string" > 'o'< / span > );
< span class = "org-type" > set< / span > (< span class = "org-variable-name" > gca< / span > ,< span class = "org-string" > 'ColorOrderIndex'< / span > ,1)
quiver(b1(1),b1(2),0.1< span class = "org-type" > *< / span > s1(1),0.1< span class = "org-type" > *< / span > s1(2))
< span class = "org-type" > set< / span > (< span class = "org-variable-name" > gca< / span > ,< span class = "org-string" > 'ColorOrderIndex'< / span > ,2)
quiver(b2(1),b2(2),0.1< span class = "org-type" > *< / span > s2(1),0.1< span class = "org-type" > *< / span > s2(2))
< span class = "org-type" > set< / span > (< span class = "org-variable-name" > gca< / span > ,< span class = "org-string" > 'ColorOrderIndex'< / span > ,3)
quiver(b3(1),b3(2),0.1< span class = "org-type" > *< / span > s3(1),0.1< span class = "org-type" > *< / span > s3(2))
plot(0, 0, < span class = "org-string" > 'ko'< / span > );
quiver([0,0],[0,0],[0.1,0],[0,0.1], < span class = "org-string" > 'k'< / span > )
plot(Ok(1), Ok(2), < span class = "org-string" > 'ro'< / span > );
quiver([Ok(1),Ok(1)],[Ok(2),Ok(2)],[0.1,0],[0,0.1], < span class = "org-string" > 'r'< / span > )
hold off;
< span class = "org-type" > axis< / span > equal;
< / pre >
< / div >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org874d920" class = "outline-3" >
< h3 id = "org874d920" > < span class = "section-number-3" > 4.5< / span > Example 2 - Stewart Platform< / h3 >
2021-02-05 13:54:57 +01:00
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-orgba9524b" class = "outline-2" >
< h2 id = "orgba9524b" > < span class = "section-number-2" > 5< / span > Stewart Platform - Simscape Model< / h2 >
2021-02-05 13:54:57 +01:00
< div class = "outline-text-2" id = "text-5" >
< p >
2021-02-05 16:18:57 +01:00
< a id = "org98421fb" > < / a >
2021-02-05 13:54:57 +01:00
< / p >
< p >
2021-02-05 16:18:57 +01:00
In this analysis, we wish to applied SVD control to the Stewart Platform shown in Figure < a href = "#org4bbff67" > 33< / a > .
2021-02-05 13:54:57 +01:00
< / p >
< p >
Some notes about the system:
< / p >
< ul class = "org-ul" >
< li > 6 voice coils actuators are used to control the motion of the top platform.< / li >
< li > the motion of the top platform is measured with a 6-axis inertial unit (3 acceleration + 3 angular accelerations)< / li >
< li > the control objective is to isolate the top platform from vibrations coming from the bottom platform< / li >
< / ul >
2021-02-05 16:18:57 +01:00
< div id = "org4bbff67" class = "figure" >
2021-02-05 13:54:57 +01:00
< p > < img src = "figs/SP_assembly.png" alt = "SP_assembly.png" / >
< / p >
< p > < span class = "figure-number" > Figure 33: < / span > Stewart Platform CAD View< / p >
< / div >
< p >
The analysis of the SVD/Jacobian control applied to the Stewart platform is performed in the following sections:
< / p >
< ul class = "org-ul" >
2021-02-05 16:18:57 +01:00
< li > Section < a href = "#orgecab5a4" > 5.1< / a > : The parameters of the Simscape model of the Stewart platform are defined< / li >
< li > Section < a href = "#org4da7956" > 5.2< / a > : The plant is identified from the Simscape model and the system coupling is shown< / li >
< li > Section < a href = "#org9f497a3" > 5.3< / a > : The plant is first decoupled using the Jacobian< / li >
< li > Section < a href = "#orgd7dd8eb" > 5.4< / a > : The decoupling is performed thanks to the SVD. To do so a real approximation of the plant is computed.< / li >
< li > Section < a href = "#orgbdea0fc" > 5.5< / a > : The effectiveness of the decoupling with the Jacobian and SVD are compared using the Gershorin Radii< / li >
< li > Section < a href = "#org2520a20" > 5.6< / a > :< / li >
< li > Section < a href = "#orgfb1d9b5" > 5.7< / a > : The dynamics of the decoupled plants are shown< / li >
< li > Section < a href = "#orgb451f57" > 5.8< / a > : A diagonal controller is defined to control the decoupled plant< / li >
< li > Section < a href = "#orgd90f32d" > 5.9< / a > : Finally, the closed loop system properties are studied< / li >
2021-02-05 13:54:57 +01:00
< / ul >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org80f9d5a" class = "outline-3" >
< h3 id = "org80f9d5a" > < span class = "section-number-3" > 5.1< / span > Simscape Model - Parameters< / h3 >
2021-02-05 13:54:57 +01:00
< div class = "outline-text-3" id = "text-5-1" >
< p >
2021-02-05 16:18:57 +01:00
< a id = "orgecab5a4" > < / a >
2021-02-05 13:54:57 +01:00
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > open(< span class = "org-string" > 'drone_platform.slx'< / span > );
< / pre >
< / div >
< p >
Definition of spring parameters:
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > kx = 0.5< span class = "org-type" > *< / span > 1e3< span class = "org-type" > /< / span > 3; < span class = "org-comment" > % [N/m]< / span >
ky = 0.5< span class = "org-type" > *< / span > 1e3< span class = "org-type" > /< / span > 3;
kz = 1e3< span class = "org-type" > /< / span > 3;
cx = 0.025; < span class = "org-comment" > % [Nm/rad]< / span >
cy = 0.025;
cz = 0.025;
< / pre >
< / div >
< p >
We suppose the sensor is perfectly positioned.
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > sens_pos_error = zeros(3,1);
< / pre >
< / div >
< p >
Gravity:
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > g = 0;
< / pre >
< / div >
< p >
We load the Jacobian (previously computed from the geometry):
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > load(< span class = "org-string" > 'jacobian.mat'< / span > , < span class = "org-string" > 'Aa'< / span > , < span class = "org-string" > 'Ab'< / span > , < span class = "org-string" > 'As'< / span > , < span class = "org-string" > 'l'< / span > , < span class = "org-string" > 'J'< / span > );
< / pre >
< / div >
< p >
We initialize other parameters:
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > U = eye(6);
V = eye(6);
Kc = tf(zeros(6));
< / pre >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "orgbf62bb3" class = "figure" >
2021-02-05 13:54:57 +01:00
< p > < img src = "figs/stewart_simscape.png" alt = "stewart_simscape.png" / >
< / p >
< p > < span class = "figure-number" > Figure 34: < / span > General view of the Simscape Model< / p >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "orgb5e7be9" class = "figure" >
2021-02-05 13:54:57 +01:00
< p > < img src = "figs/stewart_platform_details.png" alt = "stewart_platform_details.png" / >
< / p >
< p > < span class = "figure-number" > Figure 35: < / span > Simscape model of the Stewart platform< / p >
< / div >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org629e737" class = "outline-3" >
< h3 id = "org629e737" > < span class = "section-number-3" > 5.2< / span > Identification of the plant< / h3 >
2021-02-05 13:54:57 +01:00
< div class = "outline-text-3" id = "text-5-2" >
< p >
2021-02-05 16:18:57 +01:00
< a id = "org4da7956" > < / a >
2021-02-05 13:54:57 +01:00
< / p >
< p >
2021-02-05 16:18:57 +01:00
The plant shown in Figure < a href = "#org292ecdb" > 36< / a > is identified from the Simscape model.
2021-02-05 13:54:57 +01:00
< / p >
< p >
The inputs are:
< / p >
< ul class = "org-ul" >
< li > \(D_w\) translation and rotation of the bottom platform (with respect to the center of mass of the top platform)< / li >
< li > \(\tau\) the 6 forces applied by the voice coils< / li >
< / ul >
< p >
The outputs are the 6 accelerations measured by the inertial unit.
< / p >
2021-02-05 16:18:57 +01:00
< div id = "org292ecdb" class = "figure" >
2021-02-05 13:54:57 +01:00
< p > < img src = "figs/stewart_platform_plant.png" alt = "stewart_platform_plant.png" / >
< / p >
< p > < span class = "figure-number" > Figure 36: < / span > Considered plant \(\bm{G} = \begin{bmatrix}G_d\\G_u\end{bmatrix}\). \(D_w\) is the translation/rotation of the support, \(\tau\) the actuator forces, \(a\) the acceleration/angular acceleration of the top platform< / p >
< / div >
< div class = "org-src-container" >
< pre class = "src src-matlab" > < span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Name of the Simulink File< / span > < / span >
mdl = < span class = "org-string" > 'drone_platform'< / span > ;
< span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Input/Output definition< / span > < / span >
clear io; io_i = 1;
io(io_i) = linio([mdl, < span class = "org-string" > '/Dw'< / span > ], 1, < span class = "org-string" > 'openinput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1; < span class = "org-comment" > % Ground Motion< / span >
io(io_i) = linio([mdl, < span class = "org-string" > '/V-T'< / span > ], 1, < span class = "org-string" > 'openinput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1; < span class = "org-comment" > % Actuator Forces< / span >
io(io_i) = linio([mdl, < span class = "org-string" > '/Inertial Sensor'< / span > ], 1, < span class = "org-string" > 'openoutput'< / span > ); io_i = io_i < span class = "org-type" > +< / span > 1; < span class = "org-comment" > % Top platform acceleration< / span >
G = linearize(mdl, io);
G.InputName = {< span class = "org-string" > 'Dwx'< / span > , < span class = "org-string" > 'Dwy'< / span > , < span class = "org-string" > 'Dwz'< / span > , < span class = "org-string" > 'Rwx'< / span > , < span class = "org-string" > 'Rwy'< / span > , < span class = "org-string" > 'Rwz'< / span > , ...
< span class = "org-string" > 'F1'< / span > , < span class = "org-string" > 'F2'< / span > , < span class = "org-string" > 'F3'< / span > , < span class = "org-string" > 'F4'< / span > , < span class = "org-string" > 'F5'< / span > , < span class = "org-string" > 'F6'< / span > };
G.OutputName = {< span class = "org-string" > 'Ax'< / span > , < span class = "org-string" > 'Ay'< / span > , < span class = "org-string" > 'Az'< / span > , < span class = "org-string" > 'Arx'< / span > , < span class = "org-string" > 'Ary'< / span > , < span class = "org-string" > 'Arz'< / span > };
< span class = "org-comment" > % Plant< / span >
Gu = G(< span class = "org-type" > :< / span > , {< span class = "org-string" > 'F1'< / span > , < span class = "org-string" > 'F2'< / span > , < span class = "org-string" > 'F3'< / span > , < span class = "org-string" > 'F4'< / span > , < span class = "org-string" > 'F5'< / span > , < span class = "org-string" > 'F6'< / span > });
< span class = "org-comment" > % Disturbance dynamics< / span >
Gd = G(< span class = "org-type" > :< / span > , {< span class = "org-string" > 'Dwx'< / span > , < span class = "org-string" > 'Dwy'< / span > , < span class = "org-string" > 'Dwz'< / span > , < span class = "org-string" > 'Rwx'< / span > , < span class = "org-string" > 'Rwy'< / span > , < span class = "org-string" > 'Rwz'< / span > });
< / pre >
< / div >
< p >
There are 24 states (6dof for the bottom platform + 6dof for the top platform).
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > size(G)
< / pre >
< / div >
< pre class = "example" >
State-space model with 6 outputs, 12 inputs, and 24 states.
< / pre >
< p >
2021-02-05 16:18:57 +01:00
The elements of the transfer matrix \(\bm{G}\) corresponding to the transfer function from actuator forces \(\tau\) to the measured acceleration \(a\) are shown in Figure < a href = "#orgacbbdef" > 37< / a > .
2021-02-05 13:54:57 +01:00
< / p >
< p >
One can easily see that the system is strongly coupled.
< / p >
2021-02-05 16:18:57 +01:00
< div id = "orgacbbdef" class = "figure" >
2021-02-05 13:54:57 +01:00
< p > < img src = "figs/stewart_platform_coupled_plant.png" alt = "stewart_platform_coupled_plant.png" / >
< / p >
< p > < span class = "figure-number" > Figure 37: < / span > Magnitude of all 36 elements of the transfer function matrix \(G_u\)< / p >
< / div >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org5b2c266" class = "outline-3" >
< h3 id = "org5b2c266" > < span class = "section-number-3" > 5.3< / span > Decoupling using the Jacobian< / h3 >
2021-02-05 13:54:57 +01:00
< div class = "outline-text-3" id = "text-5-3" >
< p >
2021-02-05 16:18:57 +01:00
< a id = "org9f497a3" > < / a >
Consider the control architecture shown in Figure < a href = "#orgb68a424" > 38< / a > .
2021-02-05 13:54:57 +01:00
The Jacobian matrix is used to transform forces/torques applied on the top platform to the equivalent forces applied by each actuator.
< / p >
< p >
The Jacobian matrix is computed from the geometry of the platform (position and orientation of the actuators).
< / p >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< caption class = "t-above" > < span class = "table-number" > Table 10:< / span > Computed Jacobian Matrix< / caption >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 0.811< / td >
< td class = "org-right" > 0.0< / td >
< td class = "org-right" > 0.584< / td >
< td class = "org-right" > -0.018< / td >
< td class = "org-right" > -0.008< / td >
< td class = "org-right" > 0.025< / td >
< / tr >
< tr >
< td class = "org-right" > -0.406< / td >
< td class = "org-right" > -0.703< / td >
< td class = "org-right" > 0.584< / td >
< td class = "org-right" > -0.016< / td >
< td class = "org-right" > -0.012< / td >
< td class = "org-right" > -0.025< / td >
< / tr >
< tr >
< td class = "org-right" > -0.406< / td >
< td class = "org-right" > 0.703< / td >
< td class = "org-right" > 0.584< / td >
< td class = "org-right" > 0.016< / td >
< td class = "org-right" > -0.012< / td >
< td class = "org-right" > 0.025< / td >
< / tr >
< tr >
< td class = "org-right" > 0.811< / td >
< td class = "org-right" > 0.0< / td >
< td class = "org-right" > 0.584< / td >
< td class = "org-right" > 0.018< / td >
< td class = "org-right" > -0.008< / td >
< td class = "org-right" > -0.025< / td >
< / tr >
< tr >
< td class = "org-right" > -0.406< / td >
< td class = "org-right" > -0.703< / td >
< td class = "org-right" > 0.584< / td >
< td class = "org-right" > 0.002< / td >
< td class = "org-right" > 0.019< / td >
< td class = "org-right" > 0.025< / td >
< / tr >
< tr >
< td class = "org-right" > -0.406< / td >
< td class = "org-right" > 0.703< / td >
< td class = "org-right" > 0.584< / td >
< td class = "org-right" > -0.002< / td >
< td class = "org-right" > 0.019< / td >
< td class = "org-right" > -0.025< / td >
< / tr >
< / tbody >
< / table >
2021-02-05 16:18:57 +01:00
< div id = "orgb68a424" class = "figure" >
2021-02-05 13:54:57 +01:00
< p > < img src = "figs/plant_decouple_jacobian.png" alt = "plant_decouple_jacobian.png" / >
< / p >
< p > < span class = "figure-number" > Figure 38: < / span > Decoupled plant \(\bm{G}_x\) using the Jacobian matrix \(J\)< / p >
< / div >
< p >
We define a new plant:
\[ G_x(s) = G(s) J^{-T} \]
< / p >
< p >
\(G_x(s)\) correspond to the transfer function from forces and torques applied to the top platform to the absolute acceleration of the top platform.
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Gx = Gu< span class = "org-type" > *< / span > inv(J< span class = "org-type" > '< / span > );
Gx.InputName = {< span class = "org-string" > 'Fx'< / span > , < span class = "org-string" > 'Fy'< / span > , < span class = "org-string" > 'Fz'< / span > , < span class = "org-string" > 'Mx'< / span > , < span class = "org-string" > 'My'< / span > , < span class = "org-string" > 'Mz'< / span > };
< / pre >
< / div >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org31c1e90" class = "outline-3" >
< h3 id = "org31c1e90" > < span class = "section-number-3" > 5.4< / span > Decoupling using the SVD< / h3 >
2021-02-05 13:54:57 +01:00
< div class = "outline-text-3" id = "text-5-4" >
< p >
2021-02-05 16:18:57 +01:00
< a id = "orgd7dd8eb" > < / a >
2021-02-05 13:54:57 +01:00
< / p >
< p >
In order to decouple the plant using the SVD, first a real approximation of the plant transfer function matrix as the crossover frequency is required.
< / p >
< p >
Let’ s compute a real approximation of the complex matrix \(H_1\) which corresponds to the the transfer function \(G_u(j\omega_c)\) from forces applied by the actuators to the measured acceleration of the top platform evaluated at the frequency \(\omega_c\).
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > wc = 2< span class = "org-type" > *< / span > < span class = "org-constant" > pi< / span > < span class = "org-type" > *< / span > 30; < span class = "org-comment" > % Decoupling frequency [rad/s]< / span >
H1 = evalfr(Gu, < span class = "org-constant" > j< / span > < span class = "org-type" > *< / span > wc);
< / pre >
< / div >
< p >
The real approximation is computed as follows:
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > D = pinv(real(H1< span class = "org-type" > '*< / span > H1));
H1 = inv(D< span class = "org-type" > *< / span > real(H1< span class = "org-type" > '*< / span > diag(exp(< span class = "org-constant" > j< / span > < span class = "org-type" > *< / span > angle(diag(H1< span class = "org-type" > *< / span > D< span class = "org-type" > *< / span > H1< span class = "org-type" > .'< / span > ))< span class = "org-type" > /< / span > 2))));
< / pre >
< / div >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< caption class = "t-above" > < span class = "table-number" > Table 11:< / span > Real approximate of \(G\) at the decoupling frequency \(\omega_c\)< / caption >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
2020-11-06 11:59:09 +01:00
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 4.4< / td >
2021-02-05 13:54:57 +01:00
< td class = "org-right" > -2.1< / td >
< td class = "org-right" > -2.1< / td >
< td class = "org-right" > 4.4< / td >
2020-11-06 11:59:09 +01:00
< td class = "org-right" > -2.4< / td >
< td class = "org-right" > -2.4< / td >
< / tr >
< tr >
< td class = "org-right" > -0.2< / td >
< td class = "org-right" > -3.9< / td >
< td class = "org-right" > 3.9< / td >
< td class = "org-right" > 0.2< / td >
< td class = "org-right" > -3.8< / td >
< td class = "org-right" > 3.8< / td >
< / tr >
< tr >
< td class = "org-right" > 3.4< / td >
< td class = "org-right" > 3.4< / td >
< td class = "org-right" > 3.4< / td >
< td class = "org-right" > 3.4< / td >
< td class = "org-right" > 3.4< / td >
< td class = "org-right" > 3.4< / td >
< / tr >
< tr >
< td class = "org-right" > -367.1< / td >
< td class = "org-right" > -323.8< / td >
< td class = "org-right" > 323.8< / td >
< td class = "org-right" > 367.1< / td >
< td class = "org-right" > 43.3< / td >
< td class = "org-right" > -43.3< / td >
< / tr >
< tr >
< td class = "org-right" > -162.0< / td >
< td class = "org-right" > -237.0< / td >
< td class = "org-right" > -237.0< / td >
< td class = "org-right" > -162.0< / td >
< td class = "org-right" > 398.9< / td >
< td class = "org-right" > 398.9< / td >
< / tr >
< tr >
< td class = "org-right" > 220.6< / td >
< td class = "org-right" > -220.6< / td >
< td class = "org-right" > 220.6< / td >
< td class = "org-right" > -220.6< / td >
< td class = "org-right" > 220.6< / td >
< td class = "org-right" > -220.6< / td >
< / tr >
< / tbody >
< / table >
< p >
2020-11-09 14:37:04 +01:00
Note that the plant \(G_u\) at \(\omega_c\) is already an almost real matrix.
2020-11-06 11:59:09 +01:00
This can be seen on the Bode plots where the phase is close to 1.
2020-11-09 14:37:04 +01:00
This can be verified below where only the real value of \(G_u(\omega_c)\) is shown
2020-11-06 11:59:09 +01:00
< / p >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
2021-01-25 11:44:22 +01:00
< caption class = "t-above" > < span class = "table-number" > Table 12:< / span > Real part of \(G\) at the decoupling frequency \(\omega_c\)< / caption >
2020-11-06 11:59:09 +01:00
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 4.4< / td >
< td class = "org-right" > -2.1< / td >
< td class = "org-right" > -2.1< / td >
< td class = "org-right" > 4.4< / td >
< td class = "org-right" > -2.4< / td >
< td class = "org-right" > -2.4< / td >
< / tr >
< tr >
< td class = "org-right" > -0.2< / td >
< td class = "org-right" > -3.9< / td >
< td class = "org-right" > 3.9< / td >
< td class = "org-right" > 0.2< / td >
< td class = "org-right" > -3.8< / td >
< td class = "org-right" > 3.8< / td >
< / tr >
< tr >
< td class = "org-right" > 3.4< / td >
< td class = "org-right" > 3.4< / td >
< td class = "org-right" > 3.4< / td >
< td class = "org-right" > 3.4< / td >
< td class = "org-right" > 3.4< / td >
< td class = "org-right" > 3.4< / td >
< / tr >
< tr >
< td class = "org-right" > -367.1< / td >
< td class = "org-right" > -323.8< / td >
< td class = "org-right" > 323.8< / td >
< td class = "org-right" > 367.1< / td >
< td class = "org-right" > 43.3< / td >
< td class = "org-right" > -43.3< / td >
< / tr >
< tr >
< td class = "org-right" > -162.0< / td >
< td class = "org-right" > -237.0< / td >
< td class = "org-right" > -237.0< / td >
< td class = "org-right" > -162.0< / td >
< td class = "org-right" > 398.9< / td >
< td class = "org-right" > 398.9< / td >
< / tr >
< tr >
< td class = "org-right" > 220.6< / td >
< td class = "org-right" > -220.6< / td >
< td class = "org-right" > 220.6< / td >
< td class = "org-right" > -220.6< / td >
< td class = "org-right" > 220.6< / td >
< td class = "org-right" > -220.6< / td >
< / tr >
< / tbody >
< / table >
2020-09-21 18:03:40 +02:00
< p >
2020-11-25 09:40:17 +01:00
Now, the Singular Value Decomposition of \(H_1\) is performed:
2020-09-21 18:03:40 +02:00
\[ H_1 = U \Sigma V^H \]
< / p >
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > [U,< span class = "org-type" > ~< / span > ,V] = svd(H1);
2020-09-21 18:03:40 +02:00
< / pre >
< / div >
2020-11-23 18:01:13 +01:00
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
2021-01-25 11:44:22 +01:00
< caption class = "t-above" > < span class = "table-number" > Table 13:< / span > Obtained matrix \(U\)< / caption >
2020-11-23 18:01:13 +01:00
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > -0.005< / td >
< td class = "org-right" > 7e-06< / td >
< td class = "org-right" > 6e-11< / td >
< td class = "org-right" > -3e-06< / td >
< td class = "org-right" > -1< / td >
< td class = "org-right" > 0.1< / td >
< / tr >
< tr >
< td class = "org-right" > -7e-06< / td >
< td class = "org-right" > -0.005< / td >
< td class = "org-right" > -9e-09< / td >
< td class = "org-right" > -5e-09< / td >
< td class = "org-right" > -0.1< / td >
< td class = "org-right" > -1< / td >
< / tr >
< tr >
< td class = "org-right" > 4e-08< / td >
< td class = "org-right" > -2e-10< / td >
< td class = "org-right" > -6e-11< / td >
< td class = "org-right" > -1< / td >
< td class = "org-right" > 3e-06< / td >
< td class = "org-right" > -3e-07< / td >
< / tr >
< tr >
< td class = "org-right" > -0.002< / td >
< td class = "org-right" > -1< / td >
< td class = "org-right" > -5e-06< / td >
< td class = "org-right" > 2e-10< / td >
< td class = "org-right" > 0.0006< / td >
< td class = "org-right" > 0.005< / td >
< / tr >
< tr >
< td class = "org-right" > 1< / td >
< td class = "org-right" > -0.002< / td >
< td class = "org-right" > -1e-08< / td >
< td class = "org-right" > 2e-08< / td >
< td class = "org-right" > -0.005< / td >
< td class = "org-right" > 0.0006< / td >
< / tr >
< tr >
< td class = "org-right" > -4e-09< / td >
< td class = "org-right" > 5e-06< / td >
< td class = "org-right" > -1< / td >
< td class = "org-right" > 6e-11< / td >
< td class = "org-right" > -2e-09< / td >
< td class = "org-right" > -1e-08< / td >
< / tr >
< / tbody >
< / table >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
2021-01-25 11:44:22 +01:00
< caption class = "t-above" > < span class = "table-number" > Table 14:< / span > Obtained matrix \(V\)< / caption >
2020-11-23 18:01:13 +01:00
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > -0.2< / td >
< td class = "org-right" > 0.5< / td >
< td class = "org-right" > -0.4< / td >
< td class = "org-right" > -0.4< / td >
< td class = "org-right" > -0.6< / td >
< td class = "org-right" > -0.2< / td >
< / tr >
< tr >
< td class = "org-right" > -0.3< / td >
< td class = "org-right" > 0.5< / td >
< td class = "org-right" > 0.4< / td >
< td class = "org-right" > -0.4< / td >
< td class = "org-right" > 0.5< / td >
< td class = "org-right" > 0.3< / td >
< / tr >
< tr >
< td class = "org-right" > -0.3< / td >
< td class = "org-right" > -0.5< / td >
< td class = "org-right" > -0.4< / td >
< td class = "org-right" > -0.4< / td >
< td class = "org-right" > 0.4< / td >
< td class = "org-right" > -0.4< / td >
< / tr >
< tr >
< td class = "org-right" > -0.2< / td >
< td class = "org-right" > -0.5< / td >
< td class = "org-right" > 0.4< / td >
< td class = "org-right" > -0.4< / td >
< td class = "org-right" > -0.5< / td >
< td class = "org-right" > 0.3< / td >
< / tr >
< tr >
< td class = "org-right" > 0.6< / td >
< td class = "org-right" > -0.06< / td >
< td class = "org-right" > -0.4< / td >
< td class = "org-right" > -0.4< / td >
< td class = "org-right" > 0.1< / td >
< td class = "org-right" > 0.6< / td >
< / tr >
< tr >
< td class = "org-right" > 0.6< / td >
< td class = "org-right" > 0.06< / td >
< td class = "org-right" > 0.4< / td >
< td class = "org-right" > -0.4< / td >
< td class = "org-right" > -0.006< / td >
< td class = "org-right" > -0.6< / td >
< / tr >
< / tbody >
< / table >
2020-09-21 18:03:40 +02:00
< p >
2021-02-05 16:18:57 +01:00
The obtained matrices \(U\) and \(V\) are used to decouple the system as shown in Figure < a href = "#org5ad79fb" > 39< / a > .
2020-09-21 18:03:40 +02:00
< / p >
2020-11-06 16:59:03 +01:00
2021-02-05 16:18:57 +01:00
< div id = "org5ad79fb" class = "figure" >
2020-11-06 16:59:03 +01:00
< p > < img src = "figs/plant_decouple_svd.png" alt = "plant_decouple_svd.png" / >
2020-09-21 18:03:40 +02:00
< / p >
2021-02-05 13:54:57 +01:00
< p > < span class = "figure-number" > Figure 39: < / span > Decoupled plant \(\bm{G}_{SVD}\) using the Singular Value Decomposition< / p >
2020-09-21 18:03:40 +02:00
< / div >
2020-09-21 18:54:41 +02:00
< p >
2020-11-06 16:59:03 +01:00
The decoupled plant is then:
2020-11-09 14:37:04 +01:00
\[ G_{SVD}(s) = U^{-1} G_u(s) V^{-H} \]
2020-09-21 18:54:41 +02:00
< / p >
2020-11-09 14:37:04 +01:00
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > Gsvd = inv(U)< span class = "org-type" > *< / span > Gu< span class = "org-type" > *< / span > inv(V< span class = "org-type" > '< / span > );
2020-11-09 14:37:04 +01:00
< / pre >
< / div >
2020-11-06 16:59:03 +01:00
< / div >
2020-09-21 18:03:40 +02:00
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org1aa5e5e" class = "outline-3" >
< h3 id = "org1aa5e5e" > < span class = "section-number-3" > 5.5< / span > Verification of the decoupling using the “ Gershgorin Radii” < / h3 >
2021-02-05 13:54:57 +01:00
< div class = "outline-text-3" id = "text-5-5" >
2020-09-21 18:54:41 +02:00
< p >
2021-02-05 16:18:57 +01:00
< a id = "orgbdea0fc" > < / a >
2020-09-21 18:54:41 +02:00
< / p >
2020-09-21 18:03:40 +02:00
2020-11-06 16:59:03 +01:00
< p >
The “ Gershgorin Radii” is computed for the coupled plant \(G(s)\), for the “ Jacobian plant” \(G_x(s)\) and the “ SVD Decoupled Plant” \(G_{SVD}(s)\):
< / p >
2020-09-21 18:54:41 +02:00
2020-11-09 14:37:04 +01:00
< p >
The “ Gershgorin Radii” of a matrix \(S\) is defined by:
\[ \zeta_i(j\omega) = \frac{\sum\limits_{j\neq i}|S_{ij}(j\omega)|}{|S_{ii}(j\omega)|} \]
< / p >
2020-09-21 18:54:41 +02:00
< p >
2020-11-06 16:59:03 +01:00
This is computed over the following frequencies.
2020-09-21 18:54:41 +02:00
< / p >
2021-02-05 16:18:57 +01:00
< div id = "org394d419" class = "figure" >
2020-09-21 18:54:41 +02:00
< p > < img src = "figs/simscape_model_gershgorin_radii.png" alt = "simscape_model_gershgorin_radii.png" / >
< / p >
2021-02-05 13:54:57 +01:00
< p > < span class = "figure-number" > Figure 40: < / span > Gershgorin Radii of the Coupled and Decoupled plants< / p >
2020-09-21 18:54:41 +02:00
< / div >
2020-09-21 18:03:40 +02:00
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-orgb681966" class = "outline-3" >
< h3 id = "orgb681966" > < span class = "section-number-3" > 5.6< / span > Verification of the decoupling using the “ Relative Gain Array” < / h3 >
2021-02-05 13:54:57 +01:00
< div class = "outline-text-3" id = "text-5-6" >
2020-11-25 09:40:17 +01:00
< p >
2021-02-05 16:18:57 +01:00
< a id = "org2520a20" > < / a >
2020-11-25 09:40:17 +01:00
< / p >
2020-11-06 11:59:09 +01:00
< p >
2020-11-23 18:01:13 +01:00
The relative gain array (RGA) is defined as:
< / p >
\begin{equation}
\Lambda\big(G(s)\big) = G(s) \times \big( G(s)^{-1} \big)^T
\end{equation}
< p >
where \(\times\) denotes an element by element multiplication and \(G(s)\) is an \(n \times n\) square transfer matrix.
2020-11-06 11:59:09 +01:00
< / p >
2020-09-21 18:03:40 +02:00
< p >
2021-02-05 16:18:57 +01:00
The obtained RGA elements are shown in Figure < a href = "#org3c6be3d" > 41< / a > .
2020-09-21 18:03:40 +02:00
< / p >
2020-09-21 18:54:41 +02:00
2021-02-05 16:18:57 +01:00
< div id = "org3c6be3d" class = "figure" >
2020-11-23 18:01:13 +01:00
< p > < img src = "figs/simscape_model_rga.png" alt = "simscape_model_rga.png" / >
< / p >
2021-02-05 13:54:57 +01:00
< p > < span class = "figure-number" > Figure 41: < / span > Obtained norm of RGA elements for the SVD decoupled plant and the Jacobian decoupled plant< / p >
2020-11-23 18:01:13 +01:00
< / div >
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org6bea2eb" class = "outline-3" >
< h3 id = "org6bea2eb" > < span class = "section-number-3" > 5.7< / span > Obtained Decoupled Plants< / h3 >
2021-02-05 13:54:57 +01:00
< div class = "outline-text-3" id = "text-5-7" >
2020-11-23 18:01:13 +01:00
< p >
2021-02-05 16:18:57 +01:00
< a id = "orgfb1d9b5" > < / a >
2020-11-23 18:01:13 +01:00
< / p >
< p >
2021-02-05 16:18:57 +01:00
The bode plot of the diagonal and off-diagonal elements of \(G_{SVD}\) are shown in Figure < a href = "#org7492a58" > 42< / a > .
2020-11-23 18:01:13 +01:00
< / p >
2021-02-05 16:18:57 +01:00
< div id = "org7492a58" class = "figure" >
2020-09-21 18:54:41 +02:00
< p > < img src = "figs/simscape_model_decoupled_plant_svd.png" alt = "simscape_model_decoupled_plant_svd.png" / >
< / p >
2021-02-05 13:54:57 +01:00
< p > < span class = "figure-number" > Figure 42: < / span > Decoupled Plant using SVD< / p >
2020-09-21 18:54:41 +02:00
< / div >
2020-11-06 16:59:03 +01:00
< p >
2021-02-05 16:18:57 +01:00
Similarly, the bode plots of the diagonal elements and off-diagonal elements of the decoupled plant \(G_x(s)\) using the Jacobian are shown in Figure < a href = "#orgd496a8d" > 43< / a > .
2020-11-06 16:59:03 +01:00
< / p >
2020-09-21 18:54:41 +02:00
2021-02-05 16:18:57 +01:00
< div id = "orgd496a8d" class = "figure" >
2020-09-21 18:54:41 +02:00
< p > < img src = "figs/simscape_model_decoupled_plant_jacobian.png" alt = "simscape_model_decoupled_plant_jacobian.png" / >
< / p >
2021-02-05 13:54:57 +01:00
< p > < span class = "figure-number" > Figure 43: < / span > Stewart Platform Plant from forces (resp. torques) applied by the legs to the acceleration (resp. angular acceleration) of the platform as well as all the coupling terms between the two (non-diagonal terms of the transfer function matrix)< / p >
2020-09-21 18:54:41 +02:00
< / div >
2020-09-21 18:03:40 +02:00
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-orga938354" class = "outline-3" >
< h3 id = "orga938354" > < span class = "section-number-3" > 5.8< / span > Diagonal Controller< / h3 >
2021-02-05 13:54:57 +01:00
< div class = "outline-text-3" id = "text-5-8" >
2020-11-06 11:59:09 +01:00
< p >
2021-02-05 16:18:57 +01:00
< a id = "orgb451f57" > < / a >
The control diagram for the centralized control is shown in Figure < a href = "#org0789199" > 44< / a > .
2020-09-21 18:03:40 +02:00
< / p >
< p >
The controller \(K_c\) is “ working” in an cartesian frame.
The Jacobian is used to convert forces in the cartesian frame to forces applied by the actuators.
< / p >
2021-02-05 16:18:57 +01:00
< div id = "org0789199" class = "figure" >
2020-09-21 18:03:40 +02:00
< p > < img src = "figs/centralized_control.png" alt = "centralized_control.png" / >
< / p >
2021-02-05 13:54:57 +01:00
< p > < span class = "figure-number" > Figure 44: < / span > Control Diagram for the Centralized control< / p >
2020-09-21 18:03:40 +02:00
< / div >
2020-11-06 11:59:09 +01:00
< p >
2021-02-05 16:18:57 +01:00
The SVD control architecture is shown in Figure < a href = "#org07b08a4" > 45< / a > .
2020-09-21 18:03:40 +02:00
The matrices \(U\) and \(V\) are used to decoupled the plant \(G\).
< / p >
2020-11-09 10:54:46 +01:00
2021-02-05 16:18:57 +01:00
< div id = "org07b08a4" class = "figure" >
2020-09-21 18:03:40 +02:00
< p > < img src = "figs/svd_control.png" alt = "svd_control.png" / >
< / p >
2021-02-05 13:54:57 +01:00
< p > < span class = "figure-number" > Figure 45: < / span > Control Diagram for the SVD control< / p >
2020-09-21 18:03:40 +02:00
< / div >
2020-11-06 18:00:30 +01:00
2020-09-21 18:03:40 +02:00
< p >
2020-11-06 18:00:30 +01:00
We choose the controller to be a low pass filter:
\[ K_c(s) = \frac{G_0}{1 + \frac{s}{\omega_0}} \]
2020-09-21 18:03:40 +02:00
< / p >
2020-11-06 18:00:30 +01:00
< p >
\(G_0\) is tuned such that the crossover frequency corresponding to the diagonal terms of the loop gain is equal to \(\omega_c\)
< / p >
2020-09-21 18:03:40 +02:00
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > wc = 2< span class = "org-type" > *< / span > < span class = "org-constant" > pi< / span > < span class = "org-type" > *< / span > 80; < span class = "org-comment" > % Crossover Frequency [rad/s]< / span >
w0 = 2< span class = "org-type" > *< / span > < span class = "org-constant" > pi< / span > < span class = "org-type" > *< / span > 0.1; < span class = "org-comment" > % Controller Pole [rad/s]< / span >
2020-09-21 18:03:40 +02:00
< / pre >
< / div >
2020-11-06 17:02:58 +01:00
2020-11-06 18:00:30 +01:00
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > K_cen = diag(1< span class = "org-type" > ./< / span > diag(abs(evalfr(Gx, < span class = "org-constant" > j< / span > < span class = "org-type" > *< / span > wc))))< span class = "org-type" > *< / span > (1< span class = "org-type" > /< / span > abs(evalfr(1< span class = "org-type" > /< / span > (1 < span class = "org-type" > +< / span > s< span class = "org-type" > /< / span > w0), < span class = "org-constant" > j< / span > < span class = "org-type" > *< / span > wc)))< span class = "org-type" > /< / span > (1 < span class = "org-type" > +< / span > s< span class = "org-type" > /< / span > w0);
L_cen = K_cen< span class = "org-type" > *< / span > Gx;
G_cen = feedback(G, pinv(J< span class = "org-type" > '< / span > )< span class = "org-type" > *< / span > K_cen, [7< span class = "org-type" > :< / span > 12], [1< span class = "org-type" > :< / span > 6]);
2020-11-06 18:00:30 +01:00
< / pre >
< / div >
2020-11-06 17:02:58 +01:00
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > K_svd = diag(1< span class = "org-type" > ./< / span > diag(abs(evalfr(Gsvd, < span class = "org-constant" > j< / span > < span class = "org-type" > *< / span > wc))))< span class = "org-type" > *< / span > (1< span class = "org-type" > /< / span > abs(evalfr(1< span class = "org-type" > /< / span > (1 < span class = "org-type" > +< / span > s< span class = "org-type" > /< / span > w0), < span class = "org-constant" > j< / span > < span class = "org-type" > *< / span > wc)))< span class = "org-type" > /< / span > (1 < span class = "org-type" > +< / span > s< span class = "org-type" > /< / span > w0);
L_svd = K_svd< span class = "org-type" > *< / span > Gsvd;
G_svd = feedback(G, inv(V< span class = "org-type" > '< / span > )< span class = "org-type" > *< / span > K_svd< span class = "org-type" > *< / span > inv(U), [7< span class = "org-type" > :< / span > 12], [1< span class = "org-type" > :< / span > 6]);
2020-11-06 17:02:58 +01:00
< / pre >
< / div >
2020-11-06 18:00:30 +01:00
< p >
2021-02-05 16:18:57 +01:00
The obtained diagonal elements of the loop gains are shown in Figure < a href = "#org5c72e7c" > 46< / a > .
2020-11-06 18:00:30 +01:00
< / p >
2021-02-05 16:18:57 +01:00
< div id = "org5c72e7c" class = "figure" >
2020-11-06 18:00:30 +01:00
< p > < img src = "figs/stewart_comp_loop_gain_diagonal.png" alt = "stewart_comp_loop_gain_diagonal.png" / >
< / p >
2021-02-05 13:54:57 +01:00
< p > < span class = "figure-number" > Figure 46: < / span > Comparison of the diagonal elements of the loop gains for the SVD control architecture and the Jacobian one< / p >
2020-11-06 18:00:30 +01:00
< / div >
2020-09-21 18:03:40 +02:00
< / div >
< / div >
2021-02-05 16:18:57 +01:00
< div id = "outline-container-org94f7746" class = "outline-3" >
< h3 id = "org94f7746" > < span class = "section-number-3" > 5.9< / span > Closed-Loop system Performances< / h3 >
2021-02-05 13:54:57 +01:00
< div class = "outline-text-3" id = "text-5-9" >
2020-11-06 11:59:09 +01:00
< p >
2021-02-05 16:18:57 +01:00
< a id = "orgd90f32d" > < / a >
2020-11-06 11:59:09 +01:00
< / p >
2020-09-21 18:03:40 +02:00
< p >
2020-09-21 18:54:41 +02:00
Let’ s first verify the stability of the closed-loop systems:
< / p >
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > isstable(G_cen)
2020-09-21 18:54:41 +02:00
< / pre >
< / div >
< pre class = "example" >
ans =
logical
1
< / pre >
< div class = "org-src-container" >
2021-01-11 09:09:48 +01:00
< pre class = "src src-matlab" > isstable(G_svd)
2020-09-21 18:54:41 +02:00
< / pre >
< / div >
< pre class = "example" >
ans =
logical
2020-11-06 16:59:03 +01:00
1
2020-09-21 18:54:41 +02:00
< / pre >
< p >
2021-02-05 16:18:57 +01:00
The obtained transmissibility in Open-loop, for the centralized control as well as for the SVD control are shown in Figure < a href = "#org8996fc0" > 47< / a > .
2020-09-21 18:03:40 +02:00
< / p >
2021-02-05 16:18:57 +01:00
< div id = "org8996fc0" class = "figure" >
2020-09-21 18:03:40 +02:00
< p > < img src = "figs/stewart_platform_simscape_cl_transmissibility.png" alt = "stewart_platform_simscape_cl_transmissibility.png" / >
< / p >
2021-02-05 13:54:57 +01:00
< p > < span class = "figure-number" > Figure 47: < / span > Obtained Transmissibility< / p >
2020-09-21 18:03:40 +02:00
< / div >
2020-09-21 13:08:36 +02:00
< / div >
< / div >
< / div >
< / div >
< div id = "postamble" class = "status" >
< p class = "author" > Author: Dehaeze Thomas< / p >
2021-02-05 16:18:57 +01:00
< p class = "date" > Created: 2021-02-05 ven. 16:05< / p >
2020-09-21 13:08:36 +02:00
< / div >
< / body >
< / html >