2021-02-17 15:17:19 +01: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-03-05 11:48:02 +01:00
<!-- 2021 - 03 - 05 ven. 11:47 -->
2021-02-17 15:17:19 +01:00
< meta http-equiv = "Content-Type" content = "text/html;charset=utf-8" / >
< title > Diagonal control using the SVD and the Jacobian Matrix< / title >
< meta name = "author" content = "Dehaeze Thomas" / >
2021-03-05 11:48:02 +01:00
< meta name = "generator" content = "Org Mode" / >
2021-02-17 15:17:19 +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 >
< script >
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 >
< / 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" >
< h1 class = "title" > Diagonal control using the SVD and the Jacobian Matrix< / h1 >
< div id = "table-of-contents" >
< h2 > Table of Contents< / h2 >
< div id = "text-table-of-contents" >
< ul >
2021-03-05 11:48:02 +01:00
< li > < a href = "#orga5af65d" > 1. Gravimeter - Simscape Model< / a >
2021-02-17 15:17:19 +01:00
< ul >
2021-03-05 11:48:02 +01:00
< li > < a href = "#org1dfb972" > 1.1. Introduction< / a > < / li >
< li > < a href = "#org6339a4c" > 1.2. Gravimeter Model - Parameters< / a > < / li >
< li > < a href = "#org43a8481" > 1.3. System Identification< / a > < / li >
< li > < a href = "#org6f6b945" > 1.4. Decoupling using the Jacobian< / a > < / li >
< li > < a href = "#org8cada26" > 1.5. Decoupling using the SVD< / a > < / li >
< li > < a href = "#org152b61f" > 1.6. Verification of the decoupling using the “ Gershgorin Radii” < / a > < / li >
< li > < a href = "#orgdbfca2d" > 1.7. Verification of the decoupling using the “ Relative Gain Array” < / a > < / li >
< li > < a href = "#orgdd35bfa" > 1.8. Obtained Decoupled Plants< / a > < / li >
< li > < a href = "#org96129d9" > 1.9. Diagonal Controller< / a > < / li >
< li > < a href = "#org7ad3ab6" > 1.10. Closed-Loop system Performances< / a > < / li >
< li > < a href = "#orgf5b9698" > 1.11. Robustness to a change of actuator position< / a > < / li >
< li > < a href = "#orgac7da89" > 1.12. Choice of the reference frame for Jacobian decoupling< / a >
2021-02-17 15:17:19 +01:00
< ul >
2021-03-05 11:48:02 +01:00
< li > < a href = "#orgaccef52" > 1.12.1. Decoupling of the mass matrix< / a > < / li >
< li > < a href = "#org7fbd608" > 1.12.2. Decoupling of the stiffness matrix< / a > < / li >
< li > < a href = "#org0d30b70" > 1.12.3. Combined decoupling of the mass and stiffness matrices< / a > < / li >
< li > < a href = "#org7e9b46b" > 1.12.4. Conclusion< / a > < / li >
2021-02-17 15:17:19 +01:00
< / ul >
< / li >
2021-03-05 11:48:02 +01:00
< li > < a href = "#orge8453de" > 1.13. SVD decoupling performances< / a > < / li >
2021-02-17 15:17:19 +01:00
< / ul >
< / li >
2021-03-05 11:48:02 +01:00
< li > < a href = "#orgf5f43d2" > 2. Parallel Manipulator with Collocated actuator/sensor pairs< / a >
2021-02-17 15:17:19 +01:00
< ul >
2021-03-05 11:48:02 +01:00
< li > < a href = "#orgdfbc3cc" > 2.1. Model< / a > < / li >
< li > < a href = "#orgf95b075" > 2.2. The Jacobian Matrix< / a > < / li >
< li > < a href = "#org1c8a0c0" > 2.3. The Stiffness Matrix< / a > < / li >
< li > < a href = "#orgdd623fa" > 2.4. Equations of motion - Frame of the legs< / a > < / li >
< li > < a href = "#orgde21a3a" > 2.5. Equations of motion - “ Center of mass” {M}< / a > < / li >
< li > < a href = "#orgc6e87b8" > 2.6. Equations of motion - “ Center of stiffness” {K}< / a > < / li >
< li > < a href = "#org8863ba8" > 2.7. Conclusion< / a > < / li >
2021-02-17 15:17:19 +01:00
< / ul >
< / li >
2021-03-05 11:48:02 +01:00
< li > < a href = "#org155583c" > 3. SVD / Jacobian / Model decoupling comparison< / a >
2021-02-17 15:17:19 +01:00
< ul >
2021-03-05 11:48:02 +01:00
< li > < a href = "#orgca05fc9" > 3.1. Test Model< / a > < / li >
< li > < a href = "#orgc2832e4" > 3.2. Jacobian Decoupling< / a > < / li >
< li > < a href = "#org47710b8" > 3.3. Modal Decoupling< / a > < / li >
< li > < a href = "#orgfd79463" > 3.4. SVD Decoupling< / a > < / li >
< li > < a href = "#org602dfab" > 3.5. Comparison< / a >
< ul >
< li > < a href = "#org12ba525" > 3.5.1. Jacobian Decoupling< / a > < / li >
< li > < a href = "#org2c80cf5" > 3.5.2. Modal Decoupling< / a > < / li >
< li > < a href = "#org698ac80" > 3.5.3. SVD Decoupling< / a > < / li >
< / ul >
< / li >
< li > < a href = "#orgb873d8d" > 3.6. Further Notes< / a >
< ul >
< li > < a href = "#org64ecd50" > 3.6.1. Robustness of the decoupling strategies?< / a > < / li >
< li > < a href = "#org3fc4934" > 3.6.2. Other decoupling strategies< / a > < / li >
< / ul >
< / li >
< li > < a href = "#orga2f4c5e" > 3.7. Conclusion< / a > < / li >
< / ul >
< / li >
< li > < a href = "#org7f9bead" > 4. Diagonal Stiffness Matrix for a planar manipulator< / a >
< ul >
< li > < a href = "#orgadc39f3" > 4.1. Model and Assumptions< / a > < / li >
< li > < a href = "#orgcfc83c1" > 4.2. Objective< / a > < / li >
< li > < a href = "#org6d7282f" > 4.3. Conditions for Diagonal Stiffness< / a > < / li >
< li > < a href = "#org4f16201" > 4.4. Example 1 - Planar manipulator with 3 actuators< / a > < / li >
< li > < a href = "#orgad4e722" > 4.5. Example 2 - Planar manipulator with 4 actuators< / a > < / li >
2021-02-17 15:17:19 +01:00
< / ul >
< / li >
2021-03-05 11:48:02 +01:00
< li > < a href = "#orga25e46d" > 5. Diagonal Stiffness Matrix for a general parallel manipulator< / a >
2021-02-17 15:17:19 +01:00
< ul >
2021-03-05 11:48:02 +01:00
< li > < a href = "#org53d94b5" > 5.1. Model and Assumptions< / a > < / li >
< li > < a href = "#orgd2cf475" > 5.2. Objective< / a > < / li >
< li > < a href = "#orgd9290b7" > 5.3. Analytical formula of the stiffness matrix< / a > < / li >
< li > < a href = "#orgd0d0e45" > 5.4. Example 1 - 6DoF manipulator (3D)< / a > < / li >
< li > < a href = "#org32d660f" > 5.5. Example 2 - Stewart Platform< / a > < / li >
2021-02-17 15:17:19 +01:00
< / ul >
< / li >
2021-03-05 11:48:02 +01:00
< li > < a href = "#org659cc29" > 6. Stiffness and Mass Matrices in the Leg’ s frame< / a >
2021-02-17 15:17:19 +01:00
< ul >
2021-03-05 11:48:02 +01:00
< li > < a href = "#org33194e0" > 6.1. Equations< / a > < / li >
< li > < a href = "#orgc3b8547" > 6.2. Stiffness matrix< / a > < / li >
< li > < a href = "#org18755e2" > 6.3. Mass matrix< / a > < / li >
< li > < a href = "#org6f1a960" > 6.4. Planar Example< / a > < / li >
2021-02-17 15:17:19 +01:00
< / ul >
< / li >
2021-03-05 11:48:02 +01:00
< li > < a href = "#org3dbf1cd" > 7. Stewart Platform - Simscape Model< / a >
2021-02-17 15:17:19 +01:00
< ul >
2021-03-05 11:48:02 +01:00
< li > < a href = "#org4ad4383" > 7.1. Simscape Model - Parameters< / a > < / li >
< li > < a href = "#orgf3900c8" > 7.2. Identification of the plant< / a > < / li >
< li > < a href = "#orgc9d7e64" > 7.3. Decoupling using the Jacobian< / a > < / li >
< li > < a href = "#org147009c" > 7.4. Decoupling using the SVD< / a > < / li >
< li > < a href = "#org78ebd1f" > 7.5. Verification of the decoupling using the “ Gershgorin Radii” < / a > < / li >
< li > < a href = "#orgf0afb6f" > 7.6. Verification of the decoupling using the “ Relative Gain Array” < / a > < / li >
< li > < a href = "#org23869f3" > 7.7. Obtained Decoupled Plants< / a > < / li >
< li > < a href = "#org265548f" > 7.8. Diagonal Controller< / a > < / li >
< li > < a href = "#org1b19a6f" > 7.9. Closed-Loop system Performances< / a > < / li >
2021-02-17 15:17:19 +01:00
< / ul >
< / li >
< / ul >
< / div >
< / div >
< hr >
< p > This report is also available as a < a href = "./svd-control.pdf" > pdf< / a > .< / p >
< hr >
< 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-03-05 11:48:02 +01:00
< li > In Section < a href = "#org75369d1" > 1< / a > on a 3-DoF gravimeter< / li >
< li > In Section < a href = "#orgd344578" > 7< / a > on a 6-DoF Stewart platform< / li >
2021-02-17 15:17:19 +01:00
< / ul >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-orga5af65d" class = "outline-2" >
< h2 id = "orga5af65d" > < span class = "section-number-2" > 1< / span > Gravimeter - Simscape Model< / h2 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-2" id = "text-1" >
< p >
2021-03-05 11:48:02 +01:00
< a id = "org75369d1" > < / a >
2021-02-17 15:17:19 +01:00
< / p >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-org1dfb972" class = "outline-3" >
< h3 id = "org1dfb972" > < span class = "section-number-3" > 1.1< / span > Introduction< / h3 >
2021-02-17 15:17:19 +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-03-05 11:48:02 +01:00
< li > Section < a href = "#org6d12c90" > 1.2< / a > : the model is described and its parameters are defined.< / li >
< li > Section < a href = "#orgb70f136" > 1.3< / a > : the plant dynamics from the actuators to the sensors is computed from a Simscape model.< / li >
< li > Section < a href = "#org9bb78a3" > 1.4< / a > : the plant is decoupled using the Jacobian matrices.< / li >
< li > Section < a href = "#orgbac0b2b" > 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 = "#org5710571" > 1.6< / a > : the effectiveness of the decoupling is computed using the Gershorin radii< / li >
< li > Section < a href = "#orgabc7082" > 1.7< / a > : the effectiveness of the decoupling is computed using the Relative Gain Array< / li >
< li > Section < a href = "#org04bdf9e" > 1.8< / a > : the obtained decoupled plants are compared< / li >
< li > Section < a href = "#org365849e" > 1.9< / a > : the diagonal controller is developed< / li >
< li > Section < a href = "#org791bebf" > 1.10< / a > : the obtained closed-loop performances for the two methods are compared< / li >
< li > Section < a href = "#org8207b0e" > 1.11< / a > : the robustness to a change of actuator position is evaluated< / li >
< li > Section < a href = "#org22dd83b" > 1.12< / a > : the choice of the reference frame for the evaluation of the Jacobian is discussed< / li >
< li > Section < a href = "#org010ca70" > 1.13< / a > : the decoupling performances of SVD is evaluated for a low damped and an highly damped system< / li >
2021-02-17 15:17:19 +01:00
< / ul >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-org6339a4c" class = "outline-3" >
< h3 id = "org6339a4c" > < span class = "section-number-3" > 1.2< / span > Gravimeter Model - Parameters< / h3 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-3" id = "text-1-2" >
< p >
2021-03-05 11:48:02 +01:00
< a id = "org6d12c90" > < / a >
2021-02-17 15:17:19 +01:00
< / p >
< p >
2021-03-05 11:48:02 +01:00
The model of the gravimeter is schematically shown in Figure < a href = "#orgb8786f2" > 1< / a > .
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< div id = "orgb8786f2" class = "figure" >
2021-02-17 15:17:19 +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 >
2021-03-05 11:48:02 +01:00
< div id = "org1392ecf" class = "figure" >
2021-02-17 15:17:19 +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 >
< p >
The parameters used for the simulation are the following:
< / p >
< div class = "org-src-container" >
< 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 >
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 >
k = 15e3; < span class = "org-comment" > % Actuator Stiffness [N/m]< / span >
c = 2e1; < span class = "org-comment" > % Actuator Damping [N/(m/s)]< / span >
deq = 0.2; < span class = "org-comment" > % Length of the actuators [m]< / span >
g = 0; < span class = "org-comment" > % Gravity [m/s2]< / span >
< / pre >
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-org43a8481" class = "outline-3" >
< h3 id = "org43a8481" > < span class = "section-number-3" > 1.3< / span > System Identification< / h3 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-3" id = "text-1-3" >
< p >
2021-03-05 11:48:02 +01:00
< a id = "orgb70f136" > < / a >
2021-02-17 15:17:19 +01:00
< / p >
< 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" > '/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 > };
< / pre >
< / div >
< p >
2021-03-05 11:48:02 +01:00
The inputs and outputs of the plant are shown in Figure < a href = "#org2148099" > 3< / a > .
2021-02-17 15:17:19 +01:00
< / p >
< p >
More precisely there are three inputs (the three actuator forces):
< / p >
\begin{equation}
\bm{\tau} = \begin{bmatrix}\tau_1 \\ \tau_2 \\ \tau_2 \end{bmatrix}
\end{equation}
< p >
And 4 outputs (the two 2-DoF accelerometers):
< / p >
\begin{equation}
\bm{a} = \begin{bmatrix} a_{1x} \\ a_{1y} \\ a_{2x} \\ a_{2y} \end{bmatrix}
\end{equation}
2021-03-05 11:48:02 +01:00
< div id = "org2148099" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/gravimeter_plant_schematic.png" alt = "gravimeter_plant_schematic.png" / >
< / p >
< p > < span class = "figure-number" > Figure 3: < / span > Schematic of the gravimeter plant< / p >
< / div >
< p >
We can check the poles of the plant:
< / p >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< 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 >
< p >
As expected, the plant as 6 states (2 translations + 1 rotation)
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > size(G)
< / pre >
< / div >
< pre class = "example" >
State-space model with 4 outputs, 3 inputs, and 6 states.
< / pre >
< p >
2021-03-05 11:48:02 +01:00
The bode plot of all elements of the plant are shown in Figure < a href = "#org1358b5e" > 4< / a > .
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< div id = "org1358b5e" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/open_loop_tf.png" alt = "open_loop_tf.png" / >
< / p >
< p > < span class = "figure-number" > Figure 4: < / span > Open Loop Transfer Function from 3 Actuators to 4 Accelerometers< / p >
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-org6f6b945" class = "outline-3" >
< h3 id = "org6f6b945" > < span class = "section-number-3" > 1.4< / span > Decoupling using the Jacobian< / h3 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-3" id = "text-1-4" >
< p >
2021-03-05 11:48:02 +01:00
< a id = "org9bb78a3" > < / a >
2021-02-17 15:17:19 +01:00
< / p >
< p >
2021-03-05 11:48:02 +01:00
Consider the control architecture shown in Figure < a href = "#org771982f" > 5< / a > .
2021-02-17 15:17:19 +01:00
< / p >
< p >
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:
< / p >
\begin{equation}
\begin{bmatrix} \tau_1 \\ \tau_2 \\ \tau_3 \end{bmatrix} = J_{\tau}^{-T} \begin{bmatrix} F_x \\ F_y \\ M_z \end{bmatrix}
\end{equation}
< p >
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}
\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}
\end{equation}
< p >
2021-03-05 11:48:02 +01:00
We thus define a new plant as defined in Figure < a href = "#org771982f" > 5< / a > .
2021-02-17 15:17:19 +01:00
\[ \bm{G}_x(s) = J_a^{-1} \bm{G}(s) J_{\tau}^{-T} \]
< / p >
< p >
2021-03-05 11:48:02 +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 = "#org771982f" > 5< / a > ).
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< div id = "org771982f" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/gravimeter_decouple_jacobian.png" alt = "gravimeter_decouple_jacobian.png" / >
< / p >
< p > < span class = "figure-number" > Figure 5: < / span > Decoupled plant \(\bm{G}_x\) using the Jacobian matrix \(J\)< / p >
< / div >
< p >
The Jacobian corresponding to the sensors and actuators are defined below:
< / p >
< div class = "org-src-container" >
< 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];
< / pre >
< / div >
< p >
And the plant \(\bm{G}_x\) is computed:
< / p >
< div class = "org-src-container" >
< 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 > };
< / pre >
< / div >
< pre class = "example" >
size(Gx)
State-space model with 3 outputs, 3 inputs, and 6 states.
< / pre >
< p >
2021-03-05 11:48:02 +01:00
The diagonal and off-diagonal elements of \(G_x\) are shown in Figure < a href = "#org5252760" > 6< / a > .
2021-02-17 15:17:19 +01:00
< / p >
< 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-03-05 11:48:02 +01:00
The choice of the frame in this the Jacobian is evaluated is discussed in Section < a href = "#org22dd83b" > 1.12< / a > .
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< div id = "org5252760" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/gravimeter_jacobian_plant.png" alt = "gravimeter_jacobian_plant.png" / >
< / p >
< p > < span class = "figure-number" > Figure 6: < / span > Diagonal and off-diagonal elements of \(G_x\)< / p >
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-org8cada26" class = "outline-3" >
< h3 id = "org8cada26" > < span class = "section-number-3" > 1.5< / span > Decoupling using the SVD< / h3 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-3" id = "text-1-5" >
< p >
2021-03-05 11:48:02 +01:00
< a id = "orgbac0b2b" > < / a >
2021-02-17 15:17:19 +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(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 > 10; < span class = "org-comment" > % Decoupling frequency [rad/s]< / span >
H1 = evalfr(G, < 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 = 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))));
< / pre >
< / div >
< 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 >
< td class = "org-right" > 0.0092< / td >
< td class = "org-right" > -0.0039< / td >
< td class = "org-right" > 0.0039< / td >
< / tr >
< tr >
< 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 >
< / tr >
< tr >
< td class = "org-right" > 8.4e-09< / td >
< td class = "org-right" > 0.0025< / td >
< td class = "org-right" > 0.0025< / td >
< / tr >
< / tbody >
< / table >
< p >
Now, the Singular Value Decomposition of \(H_1\) is performed:
\[ H_1 = U \Sigma V^H \]
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > [U,S,V] = svd(H1);
< / pre >
< / div >
< 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 >
< p >
2021-03-05 11:48:02 +01:00
The obtained matrices \(U\) and \(V\) are used to decouple the system as shown in Figure < a href = "#org31ec2e3" > 7< / a > .
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< div id = "org31ec2e3" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/gravimeter_decouple_svd.png" alt = "gravimeter_decouple_svd.png" / >
< / p >
< p > < span class = "figure-number" > Figure 7: < / span > Decoupled plant \(\bm{G}_{SVD}\) using the Singular Value Decomposition< / p >
< / div >
< p >
The decoupled plant is then:
\[ \bm{G}_{SVD}(s) = U^{-1} \bm{G}(s) V^{-H} \]
< / p >
< div class = "org-src-container" >
< 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 > );
< / pre >
< / div >
< pre class = "example" >
size(Gsvd)
State-space model with 4 outputs, 3 inputs, and 6 states.
< / pre >
< p >
The 4th output (corresponding to the null singular value) is discarded, and we only keep the \(3 \times 3\) plant:
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Gsvd = Gsvd(1< span class = "org-type" > :< / span > 3, 1< span class = "org-type" > :< / span > 3);
< / pre >
< / div >
< p >
2021-03-05 11:48:02 +01:00
The diagonal and off-diagonal elements of the “ SVD” plant are shown in Figure < a href = "#org8ae41af" > 8< / a > .
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< div id = "org8ae41af" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/gravimeter_svd_plant.png" alt = "gravimeter_svd_plant.png" / >
< / p >
< p > < span class = "figure-number" > Figure 8: < / span > Diagonal and off-diagonal elements of \(G_{svd}\)< / p >
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-org152b61f" class = "outline-3" >
< h3 id = "org152b61f" > < span class = "section-number-3" > 1.6< / span > Verification of the decoupling using the “ Gershgorin Radii” < / h3 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-3" id = "text-1-6" >
< p >
2021-03-05 11:48:02 +01:00
< a id = "org5710571" > < / a >
2021-02-17 15:17:19 +01:00
< / p >
< 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 >
< 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 >
2021-03-05 11:48:02 +01:00
< div id = "org3a066e6" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/gravimeter_gershgorin_radii.png" alt = "gravimeter_gershgorin_radii.png" / >
< / p >
< p > < span class = "figure-number" > Figure 9: < / span > Gershgorin Radii of the Coupled and Decoupled plants< / p >
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-orgdbfca2d" class = "outline-3" >
< h3 id = "orgdbfca2d" > < span class = "section-number-3" > 1.7< / span > Verification of the decoupling using the “ Relative Gain Array” < / h3 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-3" id = "text-1-7" >
< p >
2021-03-05 11:48:02 +01:00
< a id = "orgabc7082" > < / a >
2021-02-17 15:17:19 +01:00
< / p >
< p >
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-03-05 11:48:02 +01:00
The obtained RGA elements are shown in Figure < a href = "#orgb5ce67c" > 10< / a > .
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< div id = "orgb5ce67c" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/gravimeter_rga.png" alt = "gravimeter_rga.png" / >
< / p >
< 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-03-05 11:48:02 +01:00
< div id = "orgcffcce4" class = "figure" >
2021-02-17 15:17:19 +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 >
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-orgdd35bfa" class = "outline-3" >
< h3 id = "orgdd35bfa" > < span class = "section-number-3" > 1.8< / span > Obtained Decoupled Plants< / h3 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-3" id = "text-1-8" >
< p >
2021-03-05 11:48:02 +01:00
< a id = "org04bdf9e" > < / a >
2021-02-17 15:17:19 +01:00
< / p >
< p >
2021-03-05 11:48:02 +01:00
The bode plot of the diagonal and off-diagonal elements of \(G_{SVD}\) are shown in Figure < a href = "#org7b850e8" > 12< / a > .
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< div id = "org7b850e8" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/gravimeter_decoupled_plant_svd.png" alt = "gravimeter_decoupled_plant_svd.png" / >
< / p >
< p > < span class = "figure-number" > Figure 12: < / span > Decoupled Plant using SVD< / p >
< / div >
< p >
2021-03-05 11:48:02 +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 = "#orgd323c5f" > 13< / a > .
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< div id = "orgd323c5f" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/gravimeter_decoupled_plant_jacobian.png" alt = "gravimeter_decoupled_plant_jacobian.png" / >
< / p >
< 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 >
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-org96129d9" class = "outline-3" >
< h3 id = "org96129d9" > < span class = "section-number-3" > 1.9< / span > Diagonal Controller< / h3 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-3" id = "text-1-9" >
< p >
2021-03-05 11:48:02 +01:00
< a id = "org365849e" > < / a >
The control diagram for the centralized control is shown in Figure < a href = "#org0542aab" > 14< / a > .
2021-02-17 15:17:19 +01: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-03-05 11:48:02 +01:00
< div id = "org0542aab" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/centralized_control_gravimeter.png" alt = "centralized_control_gravimeter.png" / >
< / p >
< p > < span class = "figure-number" > Figure 14: < / span > Control Diagram for the Centralized control< / p >
< / div >
< p >
2021-03-05 11:48:02 +01:00
The SVD control architecture is shown in Figure < a href = "#orgd970a8a" > 15< / a > .
2021-02-17 15:17:19 +01:00
The matrices \(U\) and \(V\) are used to decoupled the plant \(G\).
< / p >
2021-03-05 11:48:02 +01:00
< div id = "orgd970a8a" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/svd_control_gravimeter.png" alt = "svd_control_gravimeter.png" / >
< / p >
< p > < span class = "figure-number" > Figure 15: < / span > Control Diagram for the SVD control< / p >
< / div >
< p >
We choose the controller to be a low pass filter:
\[ K_c(s) = \frac{G_0}{1 + \frac{s}{\omega_0}} \]
< / p >
< 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 >
< 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 > 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 >
< / pre >
< / div >
< div class = "org-src-container" >
< 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;
< / pre >
< / div >
< div class = "org-src-container" >
< 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);
< / pre >
< / div >
< p >
2021-03-05 11:48:02 +01:00
The obtained diagonal elements of the loop gains are shown in Figure < a href = "#org333f7d8" > 16< / a > .
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< div id = "org333f7d8" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/gravimeter_comp_loop_gain_diagonal.png" alt = "gravimeter_comp_loop_gain_diagonal.png" / >
< / p >
< 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 >
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-org7ad3ab6" class = "outline-3" >
< h3 id = "org7ad3ab6" > < span class = "section-number-3" > 1.10< / span > Closed-Loop system Performances< / h3 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-3" id = "text-1-10" >
< p >
2021-03-05 11:48:02 +01:00
< a id = "org791bebf" > < / a >
2021-02-17 15:17:19 +01:00
< / p >
< 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 >
< p >
Let’ s first verify the stability of the closed-loop systems:
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > isstable(G_cen)
< / pre >
< / div >
< pre class = "example" >
ans =
logical
1
< / pre >
< div class = "org-src-container" >
< pre class = "src src-matlab" > isstable(G_svd)
< / pre >
< / div >
< pre class = "example" >
ans =
logical
1
< / pre >
< p >
2021-03-05 11:48:02 +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 = "#org3911954" > 17< / a > .
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< div id = "org3911954" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/gravimeter_platform_simscape_cl_transmissibility.png" alt = "gravimeter_platform_simscape_cl_transmissibility.png" / >
< / p >
< p > < span class = "figure-number" > Figure 17: < / span > Obtained Transmissibility< / p >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "org943a9b8" class = "figure" >
2021-02-17 15:17:19 +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-03-05 11:48:02 +01:00
< div id = "outline-container-orgf5b9698" class = "outline-3" >
< h3 id = "orgf5b9698" > < span class = "section-number-3" > 1.11< / span > Robustness to a change of actuator position< / h3 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-3" id = "text-1-11" >
< p >
2021-03-05 11:48:02 +01:00
< a id = "org8207b0e" > < / a >
2021-02-17 15:17:19 +01:00
< / p >
< p >
Let say we change the position of the actuators:
< / p >
< div class = "org-src-container" >
< 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 >
< / pre >
< / 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" > '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 >
< p >
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.
< / p >
< p >
2021-03-05 11:48:02 +01:00
The closed-loop system are still stable in both cases, and the obtained transmissibility are equivalent as shown in Figure < a href = "#org81bd59a" > 19< / a > .
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< div id = "org81bd59a" class = "figure" >
2021-02-17 15:17:19 +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-03-05 11:48:02 +01:00
< div id = "outline-container-orgac7da89" class = "outline-3" >
< h3 id = "orgac7da89" > < span class = "section-number-3" > 1.12< / span > Choice of the reference frame for Jacobian decoupling< / h3 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-3" id = "text-1-12" >
< p >
2021-03-05 11:48:02 +01:00
< a id = "org22dd83b" > < / a >
2021-02-17 15:17:19 +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.
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-03-05 11:48:02 +01:00
< div id = "outline-container-orgaccef52" class = "outline-4" >
< h4 id = "orgaccef52" > < span class = "section-number-4" > 1.12.1< / span > Decoupling of the mass matrix< / h4 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-4" id = "text-1-12-1" >
2021-03-05 11:48:02 +01:00
< div id = "orga76ddf6" class = "figure" >
2021-02-17 15:17:19 +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" >
< 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 >
< / pre >
< / 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" > '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 > };
< / pre >
< / div >
< p >
Decoupling at the CoM (Mass decoupled)
< / p >
< div class = "org-src-container" >
< 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];
< / pre >
< / div >
< div class = "org-src-container" >
< 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 > };
< / pre >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "orgb4628dd" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/jac_decoupling_M.png" alt = "jac_decoupling_M.png" / >
< / p >
< p > < span class = "figure-number" > Figure 21: < / span > Diagonal and off-diagonal elements of the decoupled plant< / p >
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-org7fbd608" class = "outline-4" >
< h4 id = "org7fbd608" > < span class = "section-number-4" > 1.12.2< / span > Decoupling of the stiffness matrix< / h4 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-4" id = "text-1-12-2" >
2021-03-05 11:48:02 +01:00
< div id = "orgec81226" class = "figure" >
2021-02-17 15:17:19 +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" >
< 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];
< / pre >
< / div >
< p >
And the plant \(\bm{G}_x\) is computed:
< / p >
< div class = "org-src-container" >
< 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 > };
< / pre >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "orgac00ec8" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/jac_decoupling_K.png" alt = "jac_decoupling_K.png" / >
< / p >
< p > < span class = "figure-number" > Figure 23: < / span > Diagonal and off-diagonal elements of the decoupled plant< / p >
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-org0d30b70" class = "outline-4" >
< h4 id = "org0d30b70" > < span class = "section-number-4" > 1.12.3< / span > Combined decoupling of the mass and stiffness matrices< / h4 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-4" id = "text-1-12-3" >
2021-03-05 11:48:02 +01:00
< div id = "orge799c76" class = "figure" >
2021-02-17 15:17:19 +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" >
< 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 >
< / pre >
< / 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" > '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 > };
< / pre >
< / div >
< div class = "org-src-container" >
< 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];
< / pre >
< / div >
< div class = "org-src-container" >
< 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 > };
< / pre >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "org3495bfc" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/jac_decoupling_KM.png" alt = "jac_decoupling_KM.png" / >
< / p >
< p > < span class = "figure-number" > Figure 25: < / span > Diagonal and off-diagonal elements of the decoupled plant< / p >
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-org7e9b46b" class = "outline-4" >
< h4 id = "org7e9b46b" > < span class = "section-number-4" > 1.12.4< / span > Conclusion< / h4 >
2021-02-17 15:17:19 +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 >
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-orge8453de" class = "outline-3" >
< h3 id = "orge8453de" > < span class = "section-number-3" > 1.13< / span > SVD decoupling performances< / h3 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-3" id = "text-1-13" >
< p >
2021-03-05 11:48:02 +01:00
< a id = "org010ca70" > < / a >
2021-02-17 15:17:19 +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-03-05 11:48:02 +01:00
Start with small damping, the obtained diagonal and off-diagonal terms are shown in Figure < a href = "#org0130b43" > 26< / a > .
2021-02-17 15:17:19 +01:00
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > c = 2e1; < span class = "org-comment" > % Actuator Damping [N/(m/s)]< / span >
< / pre >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "org0130b43" class = "figure" >
2021-02-17 15:17:19 +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-03-05 11:48:02 +01:00
Now take a larger damping, the obtained diagonal and off-diagonal terms are shown in Figure < a href = "#orgb2dc5e8" > 27< / a > .
2021-02-17 15:17:19 +01:00
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > c = 5e2; < span class = "org-comment" > % Actuator Damping [N/(m/s)]< / span >
< / pre >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "orgb2dc5e8" class = "figure" >
2021-02-17 15:17:19 +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 >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-orgf5f43d2" class = "outline-2" >
< h2 id = "orgf5f43d2" > < span class = "section-number-2" > 2< / span > Parallel Manipulator with Collocated actuator/sensor pairs< / h2 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-2" id = "text-2" >
< p >
2021-03-05 11:48:02 +01:00
< a id = "org8dcf067" > < / a >
2021-02-17 15:17:19 +01:00
< / p >
< p >
2021-03-05 11:48:02 +01:00
In this section, we will see how the Jacobian matrix can be used to decouple a specific set of mechanical systems (described in Section < a href = "#org1c971aa" > 2.1< / a > ).
2021-02-17 15:17:19 +01:00
< / p >
< p >
2021-03-05 11:48:02 +01:00
The basic decoupling architecture is shown in Figure < a href = "#org2320eb9" > 29< / a > where the Jacobian matrix is used to both compute the actuator forces from forces/torques that are to be applied in a specific defined frame, and to compute the displacement/rotation of the same mass from several sensors.
2021-02-17 15:17:19 +01:00
< / p >
< p >
2021-03-05 11:48:02 +01:00
This is rapidly explained in Section < a href = "#org08f6760" > 2.2< / a > .
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< div id = "org3e9bfe4" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/block_diagram_jacobian_decoupling.png" alt = "block_diagram_jacobian_decoupling.png" / >
< / p >
< / div >
< p >
Depending on the chosen frame, the Stiffness matrix in that particular frame can be computed.
2021-03-05 11:48:02 +01:00
This is explained in Section < a href = "#org1fc1276" > 2.3< / a > .
2021-02-17 15:17:19 +01:00
< / p >
< p >
Then three decoupling in three specific frames is studied:
< / p >
< ul class = "org-ul" >
2021-03-05 11:48:02 +01:00
< li > Section < a href = "#org748562b" > 2.4< / a > : control in the frame of the legs< / li >
< li > Section < a href = "#orgc5ee155" > 2.5< / a > : control in a frame whose origin is at the center of mass of the payload< / li >
< li > Section < a href = "#org8140754" > 2.6< / a > : control in a frame whose origin is located at the “ center of stiffness” of the system< / li >
2021-02-17 15:17:19 +01:00
< / ul >
< p >
2021-03-05 11:48:02 +01:00
Conclusions are drawn in Section < a href = "#orga4965da" > 2.7< / a > .
2021-02-17 15:17:19 +01:00
< / p >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-orgdfbc3cc" class = "outline-3" >
< h3 id = "orgdfbc3cc" > < span class = "section-number-3" > 2.1< / span > Model< / h3 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-3" id = "text-2-1" >
< p >
2021-03-05 11:48:02 +01:00
< a id = "org1c971aa" > < / a >
2021-02-17 15:17:19 +01:00
< / p >
< p >
Let’ s consider a parallel manipulator with several collocated actuator/sensors pairs.
< / p >
< p >
2021-03-05 11:48:02 +01:00
System in Figure < a href = "#org2320eb9" > 29< / a > will serve as an example.
2021-02-17 15:17:19 +01:00
< / p >
< p >
We will note:
< / p >
< ul class = "org-ul" >
< li > \(b_i\): location of the joints on the top platform< / li >
< li > \(\hat{s}_i\): unit vector corresponding to the struts direction< / 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 >
< li > \(\mathcal{L}_i\): relative displacement of the struts< / li >
< / ul >
2021-03-05 11:48:02 +01:00
< div id = "org2320eb9" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/gravimeter_model_analytical.png" alt = "gravimeter_model_analytical.png" / >
< / p >
< p > < span class = "figure-number" > Figure 29: < / span > Model of the gravimeter< / p >
< / div >
< p >
The parameters are defined as follows:
< / p >
< 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 >
< p >
Let’ s express \({}^Mb_i\) and \(\hat{s}_i\):
< / p >
\begin{align}
{}^Mb_1 & = [-l/2,\ -h_a] \\
{}^Mb_2 & = [-la, \ -h/2] \\
{}^Mb_3 & = [ la, \ -h/2]
\end{align}
\begin{align}
\hat{s}_1 & = [1,\ 0] \\
\hat{s}_2 & = [0,\ 1] \\
\hat{s}_3 & = [0,\ 1]
\end{align}
< div class = "org-src-container" >
< pre class = "src src-matlab" > s1 = [1;0];
s2 = [0;1];
s3 = [0;1];
Mb1 = [< span class = "org-type" > -< / span > l< span class = "org-type" > /< / span > 2;< span class = "org-type" > -< / span > ha];
Mb2 = [< span class = "org-type" > -< / span > la; < span class = "org-type" > -< / span > h< span class = "org-type" > /< / span > 2];
Mb3 = [ la; < span class = "org-type" > -< / span > h< span class = "org-type" > /< / span > 2];
< / pre >
< / div >
< p >
2021-03-05 11:48:02 +01:00
Frame \(\{K\}\) is chosen such that the stiffness matrix is diagonal (explained in Section < a href = "#org4c94d7c" > 4< / a > ).
2021-02-17 15:17:19 +01:00
< / p >
< p >
The positions \({}^Kb_i\) are then:
< / p >
\begin{align}
{}^Kb_1 & = [-l/2,\ 0] \\
{}^Kb_2 & = [-la, \ -h/2+h_a] \\
{}^Kb_3 & = [ la, \ -h/2+h_a]
\end{align}
< div class = "org-src-container" >
< pre class = "src src-matlab" > Kb1 = [< span class = "org-type" > -< / span > l< span class = "org-type" > /< / span > 2; 0];
Kb2 = [< span class = "org-type" > -< / span > la; < span class = "org-type" > -< / span > h< span class = "org-type" > /< / span > 2< span class = "org-type" > +< / span > ha];
Kb3 = [ la; < span class = "org-type" > -< / span > h< span class = "org-type" > /< / span > 2< span class = "org-type" > +< / span > ha];
< / pre >
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-orgf95b075" class = "outline-3" >
< h3 id = "orgf95b075" > < span class = "section-number-3" > 2.2< / span > The Jacobian Matrix< / h3 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-3" id = "text-2-2" >
< p >
2021-03-05 11:48:02 +01:00
< a id = "org08f6760" > < / a >
2021-02-17 15:17:19 +01:00
< / p >
< p >
Let’ s note:
< / p >
< ul class = "org-ul" >
< li > < p >
\(\bm{\mathcal{L}}\) the vector of actuator displacement:
< / p >
\begin{equation}
\bm{\mathcal{L}} = \begin{bmatrix} \mathcal{L}_1 \\ \mathcal{L}_2 \\ \mathcal{L}_3 \end{bmatrix}
\end{equation}< / li >
< li > < p >
\(\bm{\tau}\) the vector of actuator forces:
< / p >
\begin{equation}
\bm{\tau} = \begin{bmatrix} \tau_1 \\ \tau_2 \\ \tau_3 \end{bmatrix}
\end{equation}< / li >
< li > < p >
\(\bm{\mathcal{F}}_{\{O\}}\) the vector of forces/torques applied on the payload on expressed in frame \(\{O\}\):
< / p >
\begin{equation}
\bm{\mathcal{F}}_{\{O\}} = \begin{bmatrix} \mathcal{F}_{\{O\},x} \\ \mathcal{F}_{\{O\},y} \\ \mathcal{M}_{\{O\},z} \end{bmatrix}
\end{equation}< / li >
< li > < p >
\(\bm{\mathcal{X}}_{\{O\}}\) the vector of displacement of the payload with respect to frame \(\{O\}\):
< / p >
\begin{equation}
\bm{\mathcal{X}}_{\{O\}} = \begin{bmatrix} \mathcal{X}_{\{O\},x} \\ \mathcal{X}_{\{O\},y} \\ \mathcal{X}_{\{O\},R_z} \end{bmatrix}
\end{equation}< / li >
< / ul >
< p >
The Jacobian matrix can be used to:
< / p >
< ul class = "org-ul" >
< li > Convert joints velocity \(\dot{\mathcal{L}}\) to payload velocity and angular velocity \(\dot{\bm{\mathcal{X}}}_{\{O\}}\):
\[ \dot{\bm{\mathcal{X}}}_{\{O\}} = J_{\{O\}} \dot{\bm{\mathcal{L}}} \]< / li >
< li > Convert actuators forces \(\bm{\tau}\) to forces/torque applied on the payload \(\bm{\mathcal{F}}_{\{O\}}\):
\[ \bm{\mathcal{F}}_{\{O\}} = J_{\{O\}}^T \bm{\tau} \]< / li >
< / ul >
< p >
with \(\{O\}\) any chosen frame.
< / p >
< p >
If we consider < b > small< / b > displacements, we have an approximate relation that links the displacements (instead of velocities):
< / p >
\begin{equation}
\bm{\mathcal{X}}_{\{M\}} = J_{\{M\}} \bm{\mathcal{L}}
\end{equation}
< p >
The Jacobian can be computed as follows:
< / p >
\begin{equation}
J_{\{O\}} = \begin{bmatrix}
{}^O\hat{s}_1^T & {}^Ob_{1,x} {}^O\hat{s}_{1,y} - {}^Ob_{1,x} {}^O\hat{s}_{1,y} \\
{}^O\hat{s}_2^T & {}^Ob_{2,x} {}^O\hat{s}_{2,y} - {}^Ob_{2,x} {}^O\hat{s}_{2,y} \\
\vdots & \vdots \\
{}^O\hat{s}_n^T & {}^Ob_{n,x} {}^O\hat{s}_{n,y} - {}^Ob_{n,x} {}^O\hat{s}_{n,y} \\
\end{bmatrix}
\end{equation}
< p >
Let’ s compute the Jacobian matrix in frame \(\{M\}\) and \(\{K\}\):
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Jm = [s1< span class = "org-type" > '< / span > , Mb1(1)< span class = "org-type" > *< / span > s1(2)< span class = "org-type" > -< / span > Mb1(2)< span class = "org-type" > *< / span > s1(1);
s2< span class = "org-type" > '< / span > , Mb2(1)< span class = "org-type" > *< / span > s2(2)< span class = "org-type" > -< / span > Mb2(2)< span class = "org-type" > *< / span > s2(1);
s3< span class = "org-type" > '< / span > , Mb3(1)< span class = "org-type" > *< / span > s3(2)< span class = "org-type" > -< / span > Mb3(2)< span class = "org-type" > *< / span > s3(1)];
< / pre >
< / div >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< caption class = "t-above" > < span class = "table-number" > Table 4:< / span > Jacobian Matrix \(J_{\{M\}}\)< / caption >
< 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" > 1.7< / td >
< / tr >
< tr >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 1< / td >
< td class = "org-right" > -0.5< / td >
< / tr >
< tr >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 1< / td >
< td class = "org-right" > 0.5< / td >
< / tr >
< / tbody >
< / table >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Jk = [s1< span class = "org-type" > '< / span > , Kb1(1)< span class = "org-type" > *< / span > s1(2)< span class = "org-type" > -< / span > Kb1(2)< span class = "org-type" > *< / span > s1(1);
s2< span class = "org-type" > '< / span > , Kb2(1)< span class = "org-type" > *< / span > s2(2)< span class = "org-type" > -< / span > Kb2(2)< span class = "org-type" > *< / span > s2(1);
s3< span class = "org-type" > '< / span > , Kb3(1)< span class = "org-type" > *< / span > s3(2)< span class = "org-type" > -< / span > Kb3(2)< span class = "org-type" > *< / span > s3(1)];
< / pre >
< / div >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< caption class = "t-above" > < span class = "table-number" > Table 5:< / span > Jacobian Matrix \(J_{\{K\}}\)< / caption >
< 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.5< / td >
< / tr >
< tr >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 1< / td >
< td class = "org-right" > 0.5< / td >
< / tr >
< / tbody >
< / table >
< p >
In the frame \(\{M\}\), the Jacobian is:
< / p >
\begin{equation}
J_{\{M\}} = \begin{bmatrix} 1 & 0 & h_a \\ 0 & 1 & -l_a \\ 0 & 1 & l_a \end{bmatrix}
\end{equation}
< p >
And in frame \(\{K\}\), the Jacobian is:
< / p >
\begin{equation}
J_{\{K\}} = \begin{bmatrix} 1 & 0 & 0 \\ 0 & 1 & -l_a \\ 0 & 1 & l_a \end{bmatrix}
\end{equation}
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-org1c8a0c0" class = "outline-3" >
< h3 id = "org1c8a0c0" > < span class = "section-number-3" > 2.3< / span > The Stiffness Matrix< / h3 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-3" id = "text-2-3" >
< p >
2021-03-05 11:48:02 +01:00
< a id = "org1fc1276" > < / a >
2021-02-17 15:17:19 +01:00
< / p >
< p >
For a parallel manipulator, the stiffness matrix expressed in a frame \(\{O\}\) is:
< / p >
\begin{equation}
K_{\{O\}} = J_{\{O\}}^T \mathcal{K} J_{\{O\}}
\end{equation}
< p >
where:
< / p >
< ul class = "org-ul" >
< li > \(J_{\{O\}}\) is the Jacobian matrix expressed in frame \(\{O\}\)< / 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 >
< / ul >
< p >
We have the same thing for the damping matrix.
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Kr = diag([k1,k2,k3]);
Cr = diag([c1,c2,c3]);
< / pre >
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-orgdd623fa" class = "outline-3" >
< h3 id = "orgdd623fa" > < span class = "section-number-3" > 2.4< / span > Equations of motion - Frame of the legs< / h3 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-3" id = "text-2-4" >
< p >
2021-03-05 11:48:02 +01:00
< a id = "org748562b" > < / a >
2021-02-17 15:17:19 +01:00
< / p >
< p >
2021-03-05 11:48:02 +01:00
Applying the second Newton’ s law on the system in Figure < a href = "#org2320eb9" > 29< / a > at its center of mass \(O_M\), we obtain:
2021-02-17 15:17:19 +01:00
< / p >
\begin{equation}
\left( M_{\{M\}} s^2 + K_{\{M\}} \right) \bm{\mathcal{X}}_{\{M\}} = \bm{\mathcal{F}}_{\{M\}}
\end{equation}
< p >
with:
< / p >
< ul class = "org-ul" >
< li > \(M_{\{M\}}\) is the mass matrix expressed in \(\{M\}\):
\[ M_{\{M\}} = \begin{bmatrix}m & 0 & 0 \\ 0 & m & 0 \\ 0 & 0 & I\end{bmatrix} \]< / li >
< li > \(K_{\{M\}}\) is the stiffness matrix expressed in \(\{M\}\):
\[ K_{\{M\}} = J_{\{M\}}^T \mathcal{K} J_{\{M\}} \]< / li >
< li > \(\bm{\mathcal{X}}_{\{M\}}\) are displacements/rotations of the mass \(x\), \(y\), \(R_z\) expressed in the frame \(\{M\}\)< / li >
< li > \(\bm{\mathcal{F}}_{\{M\}}\) are forces/torques \(\mathcal{F}_x\), \(\mathcal{F}_y\), \(\mathcal{M}_z\) applied at the origin of \(\{M\}\)< / li >
< / ul >
< p >
Let’ s use the Jacobian matrix to compute the equations in terms of actuator forces \(\bm{\tau}\) and strut displacement \(\bm{\mathcal{L}}\):
< / p >
\begin{equation}
\left( M_{\{M\}} s^2 + K_{\{M\}} \right) J_{\{M\}}^{-1} \bm{\mathcal{L}} = J_{\{M\}}^T \bm{\tau}
\end{equation}
< p >
And we obtain:
< / p >
\begin{equation}
\left( J_{\{M\}}^{-T} M_{\{M\}} J_{\{M\}}^{-1} s^2 + \mathcal{K} \right) \bm{\mathcal{L}} = \bm{\tau}
\end{equation}
< p >
The transfer function \(\bm{G}(s)\) from \(\bm{\tau}\) to \(\bm{\mathcal{L}}\) is:
< / p >
\begin{equation}
\boxed{\bm{G}(s) = {\left( J_{\{M\}}^{-T} M_{\{M\}} J_{\{M\}}^{-1} s^2 + \mathcal{K} \right)}^{-1}}
\end{equation}
2021-03-05 11:48:02 +01:00
< div id = "orgd7bb153" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/gravimeter_block_decentralized.png" alt = "gravimeter_block_decentralized.png" / >
< / p >
< p > < span class = "figure-number" > Figure 30: < / span > Block diagram of the transfer function from \(\bm{\tau}\) to \(\bm{\mathcal{L}}\)< / p >
< / div >
< div class = "org-src-container" >
< pre class = "src src-matlab" > < span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Mass Matrix in frame {M}< / span > < / span >
Mm = diag([m,m,I]);
< / pre >
< / div >
< p >
Let’ s note the mass matrix in the frame of the legs:
< / p >
\begin{equation}
M_{\{L\}} = J_{\{M\}}^{-T} M_{\{M\}} J_{\{M\}}^{-1}
\end{equation}
< div class = "org-src-container" >
< pre class = "src src-matlab" > < span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Mass Matrix in the frame of the struts< / span > < / span >
Ml = inv(Jm< span class = "org-type" > '< / span > )< span class = "org-type" > *< / span > Mm< 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 6:< / span > \(M_{\{L\}}\)< / caption >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 400< / td >
< td class = "org-right" > 680< / td >
< td class = "org-right" > -680< / td >
< / tr >
< tr >
< td class = "org-right" > 680< / td >
< td class = "org-right" > 1371< / td >
< td class = "org-right" > -1171< / td >
< / tr >
< tr >
< td class = "org-right" > -680< / td >
< td class = "org-right" > -1171< / td >
< td class = "org-right" > 1371< / td >
< / tr >
< / tbody >
< / table >
< p >
As we can see, the Stiffness matrix in the frame of the legs is diagonal.
This means the plant dynamics will be diagonal at low frequency.
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Kl = diag([k1, k2, k3]);
< / pre >
< / div >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< caption class = "t-above" > < span class = "table-number" > Table 7:< / span > \(K_{\{L\}} = \mathcal{K}\)< / caption >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 15000< / 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" > 15000< / 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" > 15000< / td >
< / tr >
< / tbody >
< / table >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Cl = diag([c1, c2, c3]);
< / pre >
< / div >
< p >
2021-03-05 11:48:02 +01:00
The transfer function \(\bm{G}(s)\) from \(\bm{\tau}\) to \(\bm{\mathcal{L}}\) is defined below and its magnitude is shown in Figure < a href = "#orgcd683d0" > 31< / a > .
2021-02-17 15:17:19 +01:00
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Gl = inv(Ml< span class = "org-type" > *< / span > s< span class = "org-type" > ^< / span > 2 < span class = "org-type" > +< / span > Cl< span class = "org-type" > *< / span > s < span class = "org-type" > +< / span > Kl);
< / pre >
< / div >
< p >
We can indeed see that the system is well decoupled at low frequency.
< / p >
2021-03-05 11:48:02 +01:00
< div id = "orgcd683d0" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/plant_frame_L.png" alt = "plant_frame_L.png" / >
< / p >
< p > < span class = "figure-number" > Figure 31: < / span > Dynamics from \(\bm{\tau}\) to \(\bm{\mathcal{L}}\)< / p >
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-orgde21a3a" class = "outline-3" >
< h3 id = "orgde21a3a" > < span class = "section-number-3" > 2.5< / span > Equations of motion - “ Center of mass” {M}< / h3 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-3" id = "text-2-5" >
< p >
2021-03-05 11:48:02 +01:00
< a id = "orgc5ee155" > < / a >
2021-02-17 15:17:19 +01:00
< / p >
< p >
The equations of motion expressed in frame \(\{M\}\) are:
< / p >
\begin{equation}
\left( M_{\{M\}} s^2 + K_{\{M\}} \right) \bm{\mathcal{X}}_{\{M\}} = \bm{\mathcal{F}}_{\{M\}}
\end{equation}
< p >
And the plant from \(\bm{F}_{\{M\}}\) to \(\bm{\mathcal{X}}_{\{M\}}\) is:
< / p >
\begin{equation}
\boxed{\bm{G}_{\{X\}} = {\left( M_{\{M\}} s^2 + K_{\{M\}} \right)}^{-1}}
\end{equation}
< p >
with:
< / p >
< ul class = "org-ul" >
< li > \(M_{\{M\}}\) is the mass matrix expressed in \(\{M\}\):
\[ M_{\{M\}} = \begin{bmatrix}m & 0 & 0 \\ 0 & m & 0 \\ 0 & 0 & I\end{bmatrix} \]< / li >
< li > \(K_{\{M\}}\) is the stiffness matrix expressed in \(\{M\}\):
\[ K_{\{M\}} = J_{\{M\}}^T \mathcal{K} J_{\{M\}} \]< / li >
< / ul >
2021-03-05 11:48:02 +01:00
< div id = "org4048946" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/gravimeter_block_com.png" alt = "gravimeter_block_com.png" / >
< / p >
< p > < span class = "figure-number" > Figure 32: < / span > Block diagram of the transfer function from \(\bm{\mathcal{F}}_{\{M\}}\) to \(\bm{\mathcal{X}}_{\{M\}}\)< / p >
< / div >
< div class = "org-src-container" >
< pre class = "src src-matlab" > < span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Mass Matrix in frame {M}< / span > < / span >
Mm = diag([m,m,I]);
< / pre >
< / div >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< caption class = "t-above" > < span class = "table-number" > Table 8:< / span > Mass matrix expressed in \(\{M\}\): \(M_{\{M\}}\)< / caption >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 400< / 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" > 400< / 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" > 115< / td >
< / tr >
< / tbody >
< / table >
< div class = "org-src-container" >
< pre class = "src src-matlab" > < span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Stiffness Matrix in frame {M}< / span > < / span >
Km = Jm< span class = "org-type" > '*< / span > Kr< span class = "org-type" > *< / span > Jm;
< / pre >
< / div >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< caption class = "t-above" > < span class = "table-number" > Table 9:< / span > Stiffness matrix expressed in \(\{M\}\): \(K_{\{M\}}\)< / caption >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 15000< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 25500< / td >
< / tr >
< tr >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 30000< / td >
< td class = "org-right" > 0< / td >
< / tr >
< tr >
< td class = "org-right" > 25500< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 50850< / td >
< / tr >
< / tbody >
< / table >
< div class = "org-src-container" >
< pre class = "src src-matlab" > < span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Damping Matrix in frame {M}< / span > < / span >
Cm = Jm< span class = "org-type" > '*< / span > Cr< span class = "org-type" > *< / span > Jm;
< / pre >
< / div >
< p >
2021-03-05 11:48:02 +01:00
The plant from \(\bm{F}_{\{M\}}\) to \(\bm{\mathcal{X}}_{\{M\}}\) is defined below and its magnitude is shown in Figure < a href = "#org663781d" > 33< / a > .
2021-02-17 15:17:19 +01:00
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > < span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Plant in frame {M}< / span > < / span >
Gm = inv(Mm< span class = "org-type" > *< / span > s< span class = "org-type" > ^< / span > 2 < span class = "org-type" > +< / span > Cm< span class = "org-type" > *< / span > s < span class = "org-type" > +< / span > Km);
< / pre >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "org663781d" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/plant_frame_M.png" alt = "plant_frame_M.png" / >
< / p >
< p > < span class = "figure-number" > Figure 33: < / span > Dynamics from \(\bm{\mathcal{F}}_{\{M\}}\) to \(\bm{\mathcal{X}}_{\{M\}}\)< / p >
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-orgc6e87b8" class = "outline-3" >
< h3 id = "orgc6e87b8" > < span class = "section-number-3" > 2.6< / span > Equations of motion - “ Center of stiffness” {K}< / h3 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-3" id = "text-2-6" >
< p >
2021-03-05 11:48:02 +01:00
< a id = "org8140754" > < / a >
2021-02-17 15:17:19 +01:00
< / p >
< p >
Let’ s now express the transfer function from \(\bm{\mathcal{F}}_{\{K\}}\) to \(\bm{\mathcal{X}}_{\{K\}}\).
We start from:
< / p >
\begin{equation}
\left( M_{\{M\}} s^2 + K_{\{M\}} \right) J_{\{M\}}^{-1} \bm{\mathcal{L}} = J_{\{M\}}^T \bm{\tau}
\end{equation}
< p >
And we make use of the Jacobian \(J_{\{K\}}\) to obtain:
< / p >
\begin{equation}
\left( M_{\{M\}} s^2 + K_{\{M\}} \right) J_{\{M\}}^{-1} J_{\{K\}} \bm{\mathcal{X}}_{\{K\}} = J_{\{M\}}^T J_{\{K\}}^{-T} \bm{\mathcal{F}}_{\{K\}}
\end{equation}
< p >
And finally:
< / p >
\begin{equation}
\left( J_{\{K\}}^T J_{\{M\}}^{-T} M_{\{M\}} J_{\{M\}}^{-1} J_{\{K\}} s^2 + J_{\{K\}}^T \mathcal{K} J_{\{K\}} \right) \bm{\mathcal{X}}_{\{K\}} = \bm{\mathcal{F}}_{\{K\}}
\end{equation}
< p >
The transfer function from \(\bm{\mathcal{F}}_{\{K\}}\) to \(\bm{\mathcal{X}}_{\{K\}}\) is then:
< / p >
\begin{equation}
\boxed{\bm{G}_{\{K\}} = {\left( J_{\{K\}}^T J_{\{M\}}^{-T} M_{\{M\}} J_{\{M\}}^{-1} J_{\{K\}} s^2 + J_{\{K\}}^T \mathcal{K} J_{\{K\}} \right)}^{-1}}
\end{equation}
< p >
The frame \(\{K\}\) has been chosen such that \(J_{\{K\}}^T \mathcal{K} J_{\{K\}}\) is diagonal.
< / p >
2021-03-05 11:48:02 +01:00
< div id = "orgff2434b" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/gravimeter_block_cok.png" alt = "gravimeter_block_cok.png" / >
< / p >
< p > < span class = "figure-number" > Figure 34: < / span > Block diagram of the transfer function from \(\bm{\mathcal{F}}_{\{K\}}\) to \(\bm{\mathcal{X}}_{\{K\}}\)< / p >
< / div >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Mk = Jk< span class = "org-type" > '*< / span > inv(Jm)< span class = "org-type" > '*< / span > Mm< span class = "org-type" > *< / span > inv(Jm)< 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 10:< / span > Mass matrix expressed in \(\{K\}\): \(M_{\{K\}}\)< / caption >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 400< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > -680< / td >
< / tr >
< tr >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 400< / td >
< td class = "org-right" > 0< / td >
< / tr >
< tr >
< td class = "org-right" > -680< / td >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 1271< / td >
< / tr >
< / tbody >
< / table >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Kk = Jk< span class = "org-type" > '*< / span > Kr< 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 11:< / span > Stiffness matrix expressed in \(\{K\}\): \(K_{\{K\}}\)< / caption >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 15000< / 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" > 30000< / 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" > 7500< / td >
< / tr >
< / tbody >
< / table >
< p >
2021-03-05 11:48:02 +01:00
The plant from \(\bm{F}_{\{K\}}\) to \(\bm{\mathcal{X}}_{\{K\}}\) is defined below and its magnitude is shown in Figure < a href = "#org6a499fc" > 35< / a > .
2021-02-17 15:17:19 +01:00
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Gk = inv(Mk< span class = "org-type" > *< / span > s< span class = "org-type" > ^< / span > 2 < span class = "org-type" > +< / span > Ck< span class = "org-type" > *< / span > s < span class = "org-type" > +< / span > Kk);
< / pre >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "org6a499fc" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/plant_frame_K.png" alt = "plant_frame_K.png" / >
< / p >
< p > < span class = "figure-number" > Figure 35: < / span > Dynamics from \(\bm{\mathcal{F}}_{\{K\}}\) to \(\bm{\mathcal{X}}_{\{K\}}\)< / p >
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-org8863ba8" class = "outline-3" >
< h3 id = "org8863ba8" > < span class = "section-number-3" > 2.7< / span > Conclusion< / h3 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-3" id = "text-2-7" >
< p >
2021-03-05 11:48:02 +01:00
< a id = "orga4965da" > < / a >
2021-02-17 15:17:19 +01:00
< / p >
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-org155583c" class = "outline-2" >
< h2 id = "org155583c" > < span class = "section-number-2" > 3< / span > SVD / Jacobian / Model decoupling comparison< / h2 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-2" id = "text-3" >
< p >
2021-03-05 11:48:02 +01:00
The goal of this section is to compare the use of several methods for the decoupling of parallel manipulators.
< / p >
< p >
It is structured as follow:
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< ul class = "org-ul" >
< li > Section < a href = "#orgea45f7a" > 3.1< / a > : the model used to compare/test decoupling strategies is presented< / li >
< li > Section < a href = "#orged3298e" > 3.2< / a > : decoupling using Jacobian matrices is presented< / li >
< li > Section < a href = "#org0584216" > 3.3< / a > : modal decoupling is presented< / li >
< li > Section < a href = "#org47cf1ef" > 3.4< / a > : SVD decoupling is presented< / li >
< li > Section < a href = "#orgd23f431" > 3.5< / a > : the three decoupling methods are applied on the test model and compared< / li >
< li > Section < a href = "#orgcaeb6b7" > 3.7< / a > : conclusions are drawn on the three decoupling methods< / li >
< / ul >
2021-02-17 15:17:19 +01:00
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-orgca05fc9" class = "outline-3" >
< h3 id = "orgca05fc9" > < span class = "section-number-3" > 3.1< / span > Test Model< / h3 >
2021-02-17 15:17:19 +01:00
< div class = "outline-text-3" id = "text-3-1" >
< p >
2021-03-05 11:48:02 +01:00
< a id = "orgea45f7a" > < / a >
Let’ s consider a parallel manipulator with several collocated actuator/sensors pairs.
< / p >
< p >
System in Figure < a href = "#orge576eaf" > 36< / a > will serve as an example.
< / p >
< p >
We will note:
2021-02-17 15:17:19 +01:00
< / p >
< ul class = "org-ul" >
2021-03-05 11:48:02 +01:00
< li > \(b_i\): location of the joints on the top platform< / li >
< li > \(\hat{s}_i\): unit vector corresponding to the struts direction< / li >
2021-02-17 15:17:19 +01:00
< 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 >
2021-03-05 11:48:02 +01:00
< li > \(\mathcal{L}_i\): relative displacement of the struts< / li >
2021-02-17 15:17:19 +01:00
< / ul >
2021-03-05 11:48:02 +01:00
< div id = "orge576eaf" class = "figure" >
< p > < img src = "figs/model_test_decoupling.png" alt = "model_test_decoupling.png" / >
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< p > < span class = "figure-number" > Figure 36: < / span > Model use to compare decoupling techniques< / p >
< / div >
2021-02-17 15:17:19 +01:00
< p >
2021-03-05 11:48:02 +01:00
The parameters are defined below.
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< div class = "org-src-container" >
< pre class = "src src-matlab" > < span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% System parameters< / span > < / span >
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 >
2021-02-17 15:17:19 +01:00
2021-03-05 11:48:02 +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 >
m = 400; < span class = "org-comment" > % Mass [kg]< / span >
I = 115; < span class = "org-comment" > % Inertia [kg m^2]< / span >
< span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Actuator Damping [N/(m/s)]< / span > < / span >
c1 = 2e1;
c2 = 2e1;
c3 = 2e1;
< span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Actuator Stiffness [N/m]< / span > < / span >
k1 = 15e3;
k2 = 15e3;
k3 = 15e3;
< span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Unit vectors of the actuators< / span > < / span >
s1 = [1;0];
s2 = [0;1];
s3 = [0;1];
< span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Location of the joints< / span > < / span >
Mb1 = [< span class = "org-type" > -< / span > l< span class = "org-type" > /< / span > 2;< span class = "org-type" > -< / span > ha];
Mb2 = [< span class = "org-type" > -< / span > la; < span class = "org-type" > -< / span > h< span class = "org-type" > /< / span > 2];
Mb3 = [ la; < span class = "org-type" > -< / span > h< span class = "org-type" > /< / span > 2];
< span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Jacobian matrix< / span > < / span >
J = [s1< span class = "org-type" > '< / span > , Mb1(1)< span class = "org-type" > *< / span > s1(2)< span class = "org-type" > -< / span > Mb1(2)< span class = "org-type" > *< / span > s1(1);
s2< span class = "org-type" > '< / span > , Mb2(1)< span class = "org-type" > *< / span > s2(2)< span class = "org-type" > -< / span > Mb2(2)< span class = "org-type" > *< / span > s2(1);
s3< span class = "org-type" > '< / span > , Mb3(1)< span class = "org-type" > *< / span > s3(2)< span class = "org-type" > -< / span > Mb3(2)< span class = "org-type" > *< / span > s3(1)];
< span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Stiffnesss and Damping matrices of the struts< / span > < / span >
Kr = diag([k1,k2,k3]);
Cr = diag([c1,c2,c3]);
< / pre >
2021-02-17 15:17:19 +01:00
< / div >
2021-03-05 11:48:02 +01:00
< div class = "org-src-container" >
< pre class = "src src-matlab" > < span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Mass Matrix in frame {M}< / span > < / span >
M = diag([m,m,I]);
< span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Stiffness Matrix in frame {M}< / span > < / span >
K = J< span class = "org-type" > '*< / span > Kr< span class = "org-type" > *< / span > J;
< span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Damping Matrix in frame {M}< / span > < / span >
C = J< span class = "org-type" > '*< / span > Cr< span class = "org-type" > *< / span > J;
< / pre >
2021-02-17 15:17:19 +01:00
< / div >
2021-03-05 11:48:02 +01:00
< p >
The plant from \(\bm{\tau}\) to \(\bm{\mathcal{L}}\) is defined below
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > < span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Plant in frame {M}< / span > < / span >
G = J< span class = "org-type" > *< / span > inv(M< span class = "org-type" > *< / span > s< span class = "org-type" > ^< / span > 2 < span class = "org-type" > +< / span > C< span class = "org-type" > *< / span > s < span class = "org-type" > +< / span > K)< span class = "org-type" > *< / span > J< span class = "org-type" > '< / span > ;
< / pre >
2021-02-17 15:17:19 +01:00
< / div >
< p >
2021-03-05 11:48:02 +01:00
The magnitude of the coupled plant \(G\) is shown in Figure < a href = "#org25e601a" > 37< / a > .
< / p >
< div id = "org25e601a" class = "figure" >
< p > < img src = "figs/coupled_plant_bode.png" alt = "coupled_plant_bode.png" / >
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< p > < span class = "figure-number" > Figure 37: < / span > Magnitude of the coupled plant.< / p >
< / div >
2021-02-17 15:17:19 +01:00
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-orgc2832e4" class = "outline-3" >
< h3 id = "orgc2832e4" > < span class = "section-number-3" > 3.2< / span > Jacobian Decoupling< / h3 >
< div class = "outline-text-3" id = "text-3-2" >
2021-02-17 15:17:19 +01:00
< p >
2021-03-05 11:48:02 +01:00
< a id = "orged3298e" > < / a >
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
2021-02-17 15:17:19 +01:00
< p >
2021-03-05 11:48:02 +01:00
The Jacobian matrix can be used to:
2021-02-17 15:17:19 +01:00
< / p >
< ul class = "org-ul" >
2021-03-05 11:48:02 +01:00
< li > Convert joints velocity \(\dot{\mathcal{L}}\) to payload velocity and angular velocity \(\dot{\bm{\mathcal{X}}}_{\{O\}}\):
\[ \dot{\bm{\mathcal{X}}}_{\{O\}} = J_{\{O\}} \dot{\bm{\mathcal{L}}} \]< / li >
< li > Convert actuators forces \(\bm{\tau}\) to forces/torque applied on the payload \(\bm{\mathcal{F}}_{\{O\}}\):
\[ \bm{\mathcal{F}}_{\{O\}} = J_{\{O\}}^T \bm{\tau} \]< / li >
< / ul >
< p >
with \(\{O\}\) any chosen frame.
< / p >
< p >
By wisely choosing frame \(\{O\}\), we can obtain nice decoupling for plant:
2021-02-17 15:17:19 +01:00
< / p >
\begin{equation}
2021-03-05 11:48:02 +01:00
\bm{G}_{\{O\}} = J_{\{O\}}^{-1} \bm{G} J_{\{O\}}^{-T}
\end{equation}
< p >
The obtained plan corresponds to forces/torques applied on origin of frame \(\{O\}\) to the translation/rotation of the payload expressed in frame \(\{O\}\).
< / p >
< div id = "orgad6b355" class = "figure" >
< p > < img src = "figs/jacobian_decoupling_arch.png" alt = "jacobian_decoupling_arch.png" / >
< / p >
< p > < span class = "figure-number" > Figure 38: < / span > Block diagram of the transfer function from \(\bm{\mathcal{F}}_{\{O\}}\) to \(\bm{\mathcal{X}}_{\{O\}}\)< / p >
< / div >
< div class = "important" id = "org454256e" >
< p >
The Jacobian matrix is only based on the geometry of the system and does not depend on the physical properties such as mass and stiffness.
< / p >
< p >
The inputs and outputs of the decoupled plant \(\bm{G}_{\{O\}}\) have physical meaning:
< / p >
< ul class = "org-ul" >
< li > \(\bm{\mathcal{F}}_{\{O\}}\) are forces/torques applied on the payload at the origin of frame \(\{O\}\)< / li >
< li > \(\bm{\mathcal{X}}_{\{O\}}\) are translations/rotation of the payload expressed in frame \(\{O\}\)< / li >
2021-02-17 15:17:19 +01:00
< / ul >
< p >
2021-03-05 11:48:02 +01:00
It is then easy to include a reference tracking input that specify the wanted motion of the payload in the frame \(\{O\}\).
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< / div >
< / div >
< / div >
< div id = "outline-container-org47710b8" class = "outline-3" >
< h3 id = "org47710b8" > < span class = "section-number-3" > 3.3< / span > Modal Decoupling< / h3 >
< div class = "outline-text-3" id = "text-3-3" >
2021-02-17 15:17:19 +01:00
< p >
2021-03-05 11:48:02 +01:00
< a id = "org0584216" > < / a >
2021-02-17 15:17:19 +01:00
< / p >
< p >
2021-03-05 11:48:02 +01:00
Let’ s consider a system with the following equations of motion:
2021-02-17 15:17:19 +01:00
< / p >
\begin{equation}
2021-03-05 11:48:02 +01:00
M \bm{\ddot{x}} + C \bm{\dot{x}} + K \bm{x} = \bm{\mathcal{F}}
2021-02-17 15:17:19 +01:00
\end{equation}
< p >
2021-03-05 11:48:02 +01:00
And the measurement output is a combination of the motion variable \(\bm{x}\):
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
\begin{equation}
\bm{y} = C_{ox} \bm{x} + C_{ov} \dot{\bm{x}}
\end{equation}
2021-02-17 15:17:19 +01:00
< p >
2021-03-05 11:48:02 +01:00
Let’ s make a < b > change of variables< / b > :
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
\begin{equation}
\boxed{\bm{x} = \Phi \bm{x}_m}
\end{equation}
2021-02-17 15:17:19 +01:00
< p >
2021-03-05 11:48:02 +01:00
with:
2021-02-17 15:17:19 +01:00
< / p >
< ul class = "org-ul" >
2021-03-05 11:48:02 +01:00
< li > \(\bm{x}_m\) the modal amplitudes< / li >
< li > \(\Phi\) a matrix whose columns are the modes shapes of the system< / li >
2021-02-17 15:17:19 +01:00
< / ul >
< p >
2021-03-05 11:48:02 +01:00
And we map the actuator forces:
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
\begin{equation}
\bm{\mathcal{F}} = J^T \bm{\tau}
\end{equation}
2021-02-17 15:17:19 +01:00
< p >
2021-03-05 11:48:02 +01:00
The equations of motion become:
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
\begin{equation}
M \Phi \bm{\ddot{x}}_m + C \Phi \bm{\dot{x}}_m + K \Phi \bm{x}_m = J^T \bm{\tau}
\end{equation}
2021-02-17 15:17:19 +01:00
< p >
2021-03-05 11:48:02 +01:00
And the measured output is:
2021-02-17 15:17:19 +01:00
< / p >
\begin{equation}
2021-03-05 11:48:02 +01:00
\bm{y} = C_{ox} \Phi \bm{x}_m + C_{ov} \Phi \dot{\bm{x}}_m
2021-02-17 15:17:19 +01:00
\end{equation}
2021-03-05 11:48:02 +01:00
< p >
By pre-multiplying the EoM by \(\Phi^T\):
< / p >
2021-02-17 15:17:19 +01:00
\begin{equation}
2021-03-05 11:48:02 +01:00
\Phi^T M \Phi \bm{\ddot{x}}_m + \Phi^T C \Phi \bm{\dot{x}}_m + \Phi^T K \Phi \bm{x}_m = \Phi^T J^T \bm{\tau}
2021-02-17 15:17:19 +01:00
\end{equation}
< p >
2021-03-05 11:48:02 +01:00
And we note:
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< ul class = "org-ul" >
< li > \(M_m = \Phi^T M \Phi = \text{diag}(\mu_i)\) the modal mass matrix< / li >
< li > \(C_m = \Phi^T C \Phi = \text{diag}(2 \xi_i \mu_i \omega_i)\) (classical damping)< / li >
< li > \(K_m = \Phi^T K \Phi = \text{diag}(\mu_i \omega_i^2)\) the modal stiffness matrix< / li >
< / ul >
2021-02-17 15:17:19 +01:00
< p >
2021-03-05 11:48:02 +01:00
And we have:
2021-02-17 15:17:19 +01:00
< / p >
\begin{equation}
2021-03-05 11:48:02 +01:00
\ddot{\bm{x}}_m + 2 \Xi \Omega \dot{\bm{x}}_m + \Omega^2 \bm{x}_m = \mu^{-1} \Phi^T J^T \bm{\tau}
2021-02-17 15:17:19 +01:00
\end{equation}
2021-03-05 11:48:02 +01:00
< p >
with:
< / p >
< ul class = "org-ul" >
< li > \(\mu = \text{diag}(\mu_i)\)< / li >
< li > \(\Omega = \text{diag}(\omega_i)\)< / li >
< li > \(\Xi = \text{diag}(\xi_i)\)< / li >
< / ul >
2021-02-17 15:17:19 +01:00
< p >
2021-03-05 11:48:02 +01:00
And we call the < b > modal input matrix< / b > :
2021-02-17 15:17:19 +01:00
< / p >
\begin{equation}
2021-03-05 11:48:02 +01:00
\boxed{B_m = \mu^{-1} \Phi^T J^T}
\end{equation}
< p >
And the < b > modal output matrices< / b > :
< / p >
\begin{equation}
\boxed{C_m = C_{ox} \Phi + C_{ov} \Phi s}
2021-02-17 15:17:19 +01:00
\end{equation}
2021-03-05 11:48:02 +01:00
2021-02-17 15:17:19 +01:00
< p >
2021-03-05 11:48:02 +01:00
Let’ s note the “ modal input” :
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
\begin{equation}
\bm{\tau}_m = B_m \bm{\tau}
\end{equation}
2021-02-17 15:17:19 +01:00
< p >
2021-03-05 11:48:02 +01:00
The transfer function from \(\bm{\tau}_m\) to \(\bm{x}_m\) is:
< / p >
\begin{equation} \label{eq:modal_eq}
\boxed{\frac{\bm{x}_m}{\bm{\tau}_m} = \left( I_n s^2 + 2 \Xi \Omega s + \Omega^2 \right)^{-1}}
\end{equation}
< p >
which is a < b > diagonal< / b > transfer function matrix.
We therefore have decoupling of the dynamics from \(\bm{\tau}_m\) to \(\bm{x}_m\).
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< p >
We now expressed the transfer function from input \(\bm{\tau}\) to output \(\bm{y}\) as a function of the “ modal variables” :
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
\begin{equation}
\boxed{\frac{\bm{y}}{\bm{\tau}} = \underbrace{\left( C_{ox} + s C_{ov} \right) \Phi}_{C_m} \underbrace{\left( I_n s^2 + 2 \Xi \Omega s + \Omega^2 \right)^{-1}}_{\text{diagonal}} \underbrace{\left( \mu^{-1} \Phi^T J^T \right)}_{B_m}}
\end{equation}
2021-02-17 15:17:19 +01:00
< p >
2021-03-05 11:48:02 +01:00
By inverting \(B_m\) and \(C_m\) and using them as shown in Figure < a href = "#org216496c" > 39< / a > , we can see that we control the system in the “ modal space” in which it is decoupled.
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< div id = "org216496c" class = "figure" >
< p > < img src = "figs/decoupling_modal.png" alt = "decoupling_modal.png" / >
< / p >
< p > < span class = "figure-number" > Figure 39: < / span > Modal Decoupling Architecture< / p >
2021-02-17 15:17:19 +01:00
< / div >
< p >
2021-03-05 11:48:02 +01:00
The system \(\bm{G}_m(s)\) shown in Figure < a href = "#org216496c" > 39< / a > is diagonal \eqref{eq:modal_eq}.
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< div class = "important" id = "org57f3d1d" >
< p >
Modal decoupling requires to have the equations of motion of the system.
From the equations of motion (and more precisely the mass and stiffness matrices), the mode shapes \(\Phi\) are computed.
< / p >
2021-02-17 15:17:19 +01:00
2021-03-05 11:48:02 +01:00
< p >
Then, the system can be decoupled in the modal space.
The obtained system on the diagonal are second order resonant systems which can be easily controlled.
< / p >
2021-02-17 15:17:19 +01:00
2021-03-05 11:48:02 +01:00
< p >
Using this decoupling strategy, it is possible to control each mode individually.
< / p >
< / div >
< / div >
< / div >
< div id = "outline-container-orgfd79463" class = "outline-3" >
< h3 id = "orgfd79463" > < span class = "section-number-3" > 3.4< / span > SVD Decoupling< / h3 >
< div class = "outline-text-3" id = "text-3-4" >
< p >
< a id = "org47cf1ef" > < / a >
< / p >
< p >
Procedure:
< / p >
< ul class = "org-ul" >
< li > Identify the dynamics of the system from inputs to outputs (can be obtained experimentally)< / li >
< li > Choose a frequency where we want to decouple the system (usually, the crossover frequency is a good choice)< / li >
< / ul >
< div class = "org-src-container" >
< pre class = "src src-matlab" > < span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Decoupling frequency [rad/s]< / span > < / span >
wc = 2< span class = "org-type" > *< / span > < span class = "org-constant" > pi< / span > < span class = "org-type" > *< / span > 10;
< span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% System's response at the decoupling frequency< / span > < / span >
H1 = evalfr(G, < span class = "org-constant" > j< / span > < span class = "org-type" > *< / span > wc);
< / pre >
< / div >
< ul class = "org-ul" >
< li > Compute a real approximation of the system’ s response at that frequency< / li >
< / ul >
< div class = "org-src-container" >
< pre class = "src src-matlab" > < span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Real approximation of G(j.wc)< / span > < / span >
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))));
< / pre >
< / div >
< ul class = "org-ul" >
< li > Perform a Singular Value Decomposition of the real approximation< / li >
< / ul >
< div class = "org-src-container" >
< pre class = "src src-matlab" > [U,S,V] = svd(H1);
< / pre >
< / div >
< ul class = "org-ul" >
< li > Use the singular input and output matrices to decouple the system as shown in Figure < a href = "#org7d376d8" > 40< / a >
\[ G_{svd}(s) = U^{-1} G(s) V^{-T} \]< / li >
< / ul >
< div class = "org-src-container" >
< 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 > );
< / pre >
< / div >
< div id = "org7d376d8" class = "figure" >
< p > < img src = "figs/decoupling_svd.png" alt = "decoupling_svd.png" / >
< / p >
< p > < span class = "figure-number" > Figure 40: < / span > Decoupled plant \(\bm{G}_{SVD}\) using the Singular Value Decomposition< / p >
< / div >
< div class = "important" id = "org3f2d846" >
< p >
In order to apply the Singular Value Decomposition, we need to have the Frequency Response Function of the system, at least near the frequency where we wish to decouple the system.
The FRF can be experimentally obtained or based from a model.
< / p >
< p >
This method ensure good decoupling near the chosen frequency, but no guaranteed decoupling away from this frequency.
< / p >
< p >
Also, it depends on how good the real approximation of the FRF is, therefore it might be less good for plants with high damping.
< / p >
< p >
This method is quite general and can be applied to any type of system.
The inputs and outputs are ordered from higher gain to lower gain at the chosen frequency.
< / p >
< ul class = "org-ul" >
< li class = "off" > < code > [  ]< / code > Do we loose any physical meaning of the obtained inputs and outputs?< / li >
< li class = "off" > < code > [  ]< / code > Can we take advantage of the fact that U and V are unitary?< / li >
< / ul >
< / div >
< / div >
< / div >
< div id = "outline-container-org602dfab" class = "outline-3" >
< h3 id = "org602dfab" > < span class = "section-number-3" > 3.5< / span > Comparison< / h3 >
< div class = "outline-text-3" id = "text-3-5" >
< p >
< a id = "orgd23f431" > < / a >
< / p >
< / div >
< div id = "outline-container-org12ba525" class = "outline-4" >
< h4 id = "org12ba525" > < span class = "section-number-4" > 3.5.1< / span > Jacobian Decoupling< / h4 >
< div class = "outline-text-4" id = "text-3-5-1" >
< p >
Decoupling properties depends on the chosen frame \(\{O\}\).
< / p >
< p >
Let’ s take the CoM as the decoupling frame.
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Gx = pinv(J)< span class = "org-type" > *< / span > G< span class = "org-type" > *< / span > pinv(J< 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 > };
< / pre >
< / div >
< div id = "org5ea90c9" class = "figure" >
< p > < img src = "figs/jacobian_plant.png" alt = "jacobian_plant.png" / >
< / p >
< p > < span class = "figure-number" > Figure 41: < / span > Plant decoupled using the Jacobian matrices \(G_x(s)\)< / p >
< / div >
< / div >
< / div >
< div id = "outline-container-org2c80cf5" class = "outline-4" >
< h4 id = "org2c80cf5" > < span class = "section-number-4" > 3.5.2< / span > Modal Decoupling< / h4 >
< div class = "outline-text-4" id = "text-3-5-2" >
< p >
For the system in Figure < a href = "#orge576eaf" > 36< / a > , we have:
< / p >
\begin{align}
\bm{x} & = \begin{bmatrix} x \\ y \\ R_z \end{bmatrix} \\
\bm{y} & = \mathcal{L} = J \bm{x}; \quad C_{ox} = J; \quad C_{ov} = 0 \\
M & = \begin{bmatrix}
m & 0 & 0 \\
0 & m & 0 \\
0 & 0 & I
\end{bmatrix}; \quad K = J' \begin{bmatrix}
k & 0 & 0 \\
0 & k & 0 \\
0 & 0 & k
\end{bmatrix} J; \quad C = J' \begin{bmatrix}
c & 0 & 0 \\
0 & c & 0 \\
0 & 0 & c
\end{bmatrix} J
\end{align}
< p >
In order to apply the architecture shown in Figure < a href = "#org216496c" > 39< / a > , we need to compute \(C_{ox}\), \(C_{ov}\), \(\Phi\), \(\mu\) and \(J\).
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > < span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Modal Decomposition< / span > < / span >
[V,D] = eig(M< span class = "org-type" > \< / span > K);
< span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Modal Mass Matrix< / span > < / span >
mu = V< span class = "org-type" > '*< / span > M< span class = "org-type" > *< / span > V;
< span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Modal output matrix< / span > < / span >
Cm = J< span class = "org-type" > *< / span > V;
< span class = "org-matlab-cellbreak" > < span class = "org-comment" > %% Modal input matrix< / span > < / span >
Bm = inv(mu)< span class = "org-type" > *< / span > V< span class = "org-type" > '*< / span > J< span class = "org-type" > '< / span > ;
< / pre >
< / div >
< table id = "org9ae3f01" border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< caption class = "t-above" > < span class = "table-number" > Table 12:< / span > \(B_m\) matrix< / caption >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > -0.0004< / td >
< td class = "org-right" > -0.0007< / td >
< td class = "org-right" > 0.0007< / td >
< / tr >
< tr >
< td class = "org-right" > -0.0151< / td >
< td class = "org-right" > 0.0041< / td >
< td class = "org-right" > -0.0041< / td >
< / tr >
< tr >
< td class = "org-right" > 0.0< / td >
< td class = "org-right" > 0.0025< / td >
< td class = "org-right" > 0.0025< / td >
< / tr >
< / tbody >
< / table >
< table id = "orgc2c577f" border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< caption class = "t-above" > < span class = "table-number" > Table 13:< / span > \(C_m\) matrix< / caption >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > -0.1< / td >
< td class = "org-right" > -1.8< / td >
< td class = "org-right" > 0.0< / td >
< / tr >
< tr >
< td class = "org-right" > -0.2< / td >
< td class = "org-right" > 0.5< / td >
< td class = "org-right" > 1.0< / td >
< / tr >
< tr >
< td class = "org-right" > 0.2< / td >
< td class = "org-right" > -0.5< / td >
< td class = "org-right" > 1.0< / td >
< / tr >
< / tbody >
< / table >
< p >
And the plant in the modal space is defined below and its magnitude is shown in Figure < a href = "#org59b6b0c" > 42< / a > .
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Gm = inv(Cm)< span class = "org-type" > *< / span > G< span class = "org-type" > *< / span > inv(Bm);
< / pre >
< / div >
< div id = "org59b6b0c" class = "figure" >
< p > < img src = "figs/modal_plant.png" alt = "modal_plant.png" / >
< / p >
< p > < span class = "figure-number" > Figure 42: < / span > Modal plant \(G_m(s)\)< / p >
< / div >
< p >
Let’ s now close one loop at a time and see how the transmissibility changes.
< / p >
< / div >
< / div >
< div id = "outline-container-org698ac80" class = "outline-4" >
< h4 id = "org698ac80" > < span class = "section-number-4" > 3.5.3< / span > SVD Decoupling< / h4 >
< div class = "outline-text-4" id = "text-3-5-3" >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< caption class = "t-above" > < span class = "table-number" > Table 14:< / 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 >
< td class = "org-right" > -8e-06< / td >
< td class = "org-right" > 2.1e-06< / td >
< td class = "org-right" > -2.1e-06< / td >
< / tr >
< tr >
< td class = "org-right" > 2.1e-06< / td >
< td class = "org-right" > -1.3e-06< / td >
< td class = "org-right" > -2.5e-08< / td >
< / tr >
< tr >
< td class = "org-right" > -2.1e-06< / td >
< td class = "org-right" > -2.5e-08< / td >
< td class = "org-right" > -1.3e-06< / td >
< / tr >
< / tbody >
< / table >
< div id = "org5274340" class = "figure" >
< p > < img src = "figs/svd_plant.png" alt = "svd_plant.png" / >
< / p >
< p > < span class = "figure-number" > Figure 43: < / span > Svd plant \(G_m(s)\)< / p >
< / div >
< / div >
< / div >
< / div >
< div id = "outline-container-orgb873d8d" class = "outline-3" >
< h3 id = "orgb873d8d" > < span class = "section-number-3" > 3.6< / span > Further Notes< / h3 >
< div class = "outline-text-3" id = "text-3-6" >
< / div >
< div id = "outline-container-org64ecd50" class = "outline-4" >
< h4 id = "org64ecd50" > < span class = "section-number-4" > 3.6.1< / span > Robustness of the decoupling strategies?< / h4 >
< div class = "outline-text-4" id = "text-3-6-1" >
< p >
What happens if we have an additional resonance in the system (Figure < a href = "#org8218471" > 44< / a > ).
< / p >
< p >
Less actuator than DoF:
< / p >
< ul class = "org-ul" >
< li > modal decoupling: can still control first \(n\) modes?< / li >
< li > SVD decoupling: does not matter< / li >
< li > Jacobian decoupling: could give poor decoupling?< / li >
< / ul >
< div id = "org8218471" class = "figure" >
< p > < img src = "figs/model_test_decoupling_spurious_res.png" alt = "model_test_decoupling_spurious_res.png" / >
< / p >
< p > < span class = "figure-number" > Figure 44: < / span > Plant with spurious resonance (additional DoF)< / p >
< / div >
< / div >
< / div >
< div id = "outline-container-org3fc4934" class = "outline-4" >
< h4 id = "org3fc4934" > < span class = "section-number-4" > 3.6.2< / span > Other decoupling strategies< / h4 >
< div class = "outline-text-4" id = "text-3-6-2" >
< ul class = "org-ul" >
< li > DC decoupling: pre-multiply the plant by \(G(0)^{-1}\)< / li >
< li > full decoupling: pre-multiply the plant by \(G(s)^{-1}\)< / li >
< / ul >
< / div >
< / div >
< / div >
< div id = "outline-container-orga2f4c5e" class = "outline-3" >
< h3 id = "orga2f4c5e" > < span class = "section-number-3" > 3.7< / span > Conclusion< / h3 >
< div class = "outline-text-3" id = "text-3-7" >
< p >
< a id = "orgcaeb6b7" > < / a >
< / p >
< p >
The three proposed methods clearly have a lot in common as they all tend to make system more decoupled by pre and/or post multiplying by a constant matrix
However, the three methods also differs by a number of points which are summarized in Table < a href = "#orgff05349" > 15< / a > .
< / p >
< table id = "orgff05349" border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< caption class = "t-above" > < span class = "table-number" > Table 15:< / span > Comparison of decoupling strategies< / caption >
< colgroup >
< col class = "org-left" / >
< col class = "org-left" / >
< col class = "org-left" / >
< col class = "org-left" / >
< / colgroup >
< thead >
< tr >
< th scope = "col" class = "org-left" >   < / th >
< th scope = "col" class = "org-left" > < b > Jacobian< / b > < / th >
< th scope = "col" class = "org-left" > < b > Modal< / b > < / th >
< th scope = "col" class = "org-left" > < b > SVD< / b > < / th >
< / tr >
< / thead >
< tbody >
< tr >
< td class = "org-left" > < b > Philosophy< / b > < / td >
< td class = "org-left" > Topology Driven< / td >
< td class = "org-left" > Physics Driven< / td >
< td class = "org-left" > Data Driven< / td >
< / tr >
< / tbody >
< tbody >
< tr >
< td class = "org-left" > < b > Requirements< / b > < / td >
< td class = "org-left" > Known geometry< / td >
< td class = "org-left" > Known equations of motion< / td >
< td class = "org-left" > Identified FRF< / td >
< / tr >
< / tbody >
< tbody >
< tr >
< td class = "org-left" > < b > Decoupling Matrices< / b > < / td >
< td class = "org-left" > Decoupling using \(J\) obtained from geometry< / td >
< td class = "org-left" > Decoupling using \(\Phi\) obtained from modal decomposition< / td >
< td class = "org-left" > Decoupling using \(U\) and \(V\) obtained from SVD< / td >
< / tr >
< / tbody >
< tbody >
< tr >
< td class = "org-left" > < b > Decoupled Plant< / b > < / td >
< td class = "org-left" > \(\bm{G}_{\{O\}} = J_{\{O\}}^{-1} \bm{G} J_{\{O\}}^{-T}\)< / td >
< td class = "org-left" > \(\bm{G}_m = C_m^{-1} \bm{G} B_m^{-1}\)< / td >
< td class = "org-left" > \(\bm{G}_{svd}(s) = U^{-1} \bm{G}(s) V^{-T}\)< / td >
< / tr >
< / tbody >
< tbody >
< tr >
< td class = "org-left" > < b > Implemented Controller< / b > < / td >
< td class = "org-left" > \(\bm{K}_{\{O\}} = J_{\{O\}}^{-T} \bm{K}_{d}(s) J_{\{O\}}^{-1}\)< / td >
< td class = "org-left" > \(\bm{K}_m = B_m^{-1} \bm{K}_{d}(s) C_m^{-1}\)< / td >
< td class = "org-left" > \(\bm{K}_{svd}(s) = V^{-T} \bm{K}_{d}(s) U^{-1}\)< / td >
< / tr >
< / tbody >
< tbody >
< tr >
< td class = "org-left" > < b > Physical Interpretation< / b > < / td >
< td class = "org-left" > Forces/Torques to Displacement/Rotation in chosen frame< / td >
< td class = "org-left" > Inputs to excite individual modes< / td >
< td class = "org-left" > Directions of max to min controllability/observability< / td >
< / tr >
< tr >
< td class = "org-left" >   < / td >
< td class = "org-left" >   < / td >
< td class = "org-left" > Output to sense individual modes< / td >
< td class = "org-left" >   < / td >
< / tr >
< / tbody >
< tbody >
< tr >
< td class = "org-left" > < b > Decoupling Properties< / b > < / td >
< td class = "org-left" > Decoupling at low or high frequency depending on the chosen frame< / td >
< td class = "org-left" > Good decoupling at all frequencies< / td >
< td class = "org-left" > Good decoupling near the chosen frequency< / td >
< / tr >
< / tbody >
< tbody >
< tr >
< td class = "org-left" > < b > Pros< / b > < / td >
< td class = "org-left" > Physical inputs / outputs< / td >
< td class = "org-left" > Target specific modes< / td >
< td class = "org-left" > Good Decoupling near the crossover< / td >
< / tr >
< tr >
< td class = "org-left" >   < / td >
< td class = "org-left" > Good decoupling at High frequency (diagonal mass matrix if Jacobian taken at the CoM)< / td >
< td class = "org-left" > 2nd order diagonal plant< / td >
< td class = "org-left" > Very General< / td >
< / tr >
< tr >
< td class = "org-left" >   < / td >
< td class = "org-left" > Good decoupling at Low frequency (if Jacobian taken at specific point)< / td >
< td class = "org-left" >   < / td >
< td class = "org-left" >   < / td >
< / tr >
< tr >
< td class = "org-left" >   < / td >
< td class = "org-left" > Easy integration of meaningful reference inputs< / td >
< td class = "org-left" >   < / td >
< td class = "org-left" >   < / td >
< / tr >
< tr >
< td class = "org-left" >   < / td >
< td class = "org-left" >   < / td >
< td class = "org-left" >   < / td >
< td class = "org-left" >   < / td >
< / tr >
< / tbody >
< tbody >
< tr >
< td class = "org-left" > < b > Cons< / b > < / td >
< td class = "org-left" > Coupling between force/rotation may be high at low frequency (non diagonal terms in K)< / td >
< td class = "org-left" > Need analytical equations< / td >
< td class = "org-left" > Loose the physical meaning of inputs /outputs< / td >
< / tr >
< tr >
< td class = "org-left" >   < / td >
< td class = "org-left" > Limited to parallel mechanisms (?)< / td >
< td class = "org-left" >   < / td >
< td class = "org-left" > Decoupling depends on the real approximation validity< / td >
< / tr >
< tr >
< td class = "org-left" >   < / td >
< td class = "org-left" > If good decoupling at all frequencies => requires specific mechanical architecture< / td >
< td class = "org-left" >   < / td >
< td class = "org-left" >   < / td >
< / tr >
< / tbody >
< tbody >
< tr >
< td class = "org-left" > < b > Applicability< / b > < / td >
< td class = "org-left" > Parallel Mechanisms< / td >
< td class = "org-left" > Systems whose dynamics that can be expressed with M and K matrices< / td >
< td class = "org-left" > Very general< / td >
< / tr >
< tr >
< td class = "org-left" >   < / td >
< td class = "org-left" > Only small motion for the Jacobian matrix to stay constant< / td >
< td class = "org-left" >   < / td >
< td class = "org-left" > Need FRF data (either experimentally or analytically)< / td >
< / tr >
< / tbody >
< / table >
< / div >
< / div >
< / div >
< div id = "outline-container-org7f9bead" class = "outline-2" >
< h2 id = "org7f9bead" > < span class = "section-number-2" > 4< / span > Diagonal Stiffness Matrix for a planar manipulator< / h2 >
< div class = "outline-text-2" id = "text-4" >
< p >
< a id = "org4c94d7c" > < / a >
< / p >
< / div >
< div id = "outline-container-orgadc39f3" class = "outline-3" >
< h3 id = "orgadc39f3" > < span class = "section-number-3" > 4.1< / span > Model and Assumptions< / h3 >
< div class = "outline-text-3" id = "text-4-1" >
< p >
Consider a 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 >
As an example, take the system shown in Figure < a href = "#org5b2b9d0" > 45< / a > .
< / p >
< div id = "org5b2b9d0" class = "figure" >
< p > < img src = "figs/3dof_model_fully_parallel.png" alt = "3dof_model_fully_parallel.png" / >
< / p >
< p > < span class = "figure-number" > Figure 45: < / span > Example of 3DoF parallel platform< / p >
< / div >
< / div >
< / div >
< div id = "outline-container-orgcfc83c1" class = "outline-3" >
< h3 id = "orgcfc83c1" > < span class = "section-number-3" > 4.2< / span > Objective< / h3 >
< 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 >
< div id = "outline-container-org6d7282f" class = "outline-3" >
< h3 id = "org6d7282f" > < span class = "section-number-3" > 4.3< / span > Conditions for Diagonal Stiffness< / h3 >
< div class = "outline-text-3" id = "text-4-3" >
< p >
The stiffness matrix in the frame \(\{K\}\) can be expressed as:
< / p >
\begin{equation} \label{eq:stiffness_formula_planar}
K_{\{K\}} = J_{\{K\}}^T \mathcal{K} J_{\{K\}}
\end{equation}
< p >
where:
< / p >
< ul class = "org-ul" >
< 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 >
< / ul >
< p >
The Jacobian for a planar manipulator, evaluated in a frame \(\{K\}\), can be expressed as follows:
< / p >
\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}
< p >
Let’ s omit the mention of frame, it is assumed that vectors are expressed in frame \(\{K\}\).
It is specified otherwise.
< / p >
< p >
Injecting \eqref{eq:jacobian_planar} into \eqref{eq:stiffness_formula_planar} yields:
< / 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,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}
< p >
In order to have a decoupled stiffness matrix, we have the following two conditions:
< / p >
\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}
< p >
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.
< / p >
< p >
Condition \eqref{eq:diag_cond_2D_1}:
< / p >
< ul class = "org-ul" >
< 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 >
< / ul >
< p >
Condition \eqref{eq:diag_cond_2D_2}:
< / p >
< 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 >
< 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 >
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}
< p >
And we have two sets of linear equations of two unknowns.
< / p >
< 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}
< 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}
< p >
Note that a rotation of the frame \(\{K\}\) with respect to frame \(\{M\}\) would make not change on the “ diagonality” of \(K_{\{K\}}\).
< / p >
< / div >
< / div >
< div id = "outline-container-org4f16201" class = "outline-3" >
< h3 id = "org4f16201" > < span class = "section-number-3" > 4.4< / span > Example 1 - Planar manipulator with 3 actuators< / h3 >
< div class = "outline-text-3" id = "text-4-4" >
< p >
Consider system of Figure < a href = "#org0da4317" > 46< / a > .
< / p >
< div id = "org0da4317" class = "figure" >
< p > < img src = "figs/3dof_model_fully_parallel.png" alt = "3dof_model_fully_parallel.png" / >
< / p >
< p > < span class = "figure-number" > Figure 46: < / span > Example of 3DoF parallel platform< / p >
< / div >
< p >
The stiffnesses \(k_i\), the joint positions \({}^Mb_i\) and joint unit vectors \({}^M\hat{s}_i\) are defined below:
< / p >
< 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 >
< p >
Let’ s first verify that condition \eqref{eq:diag_cond_2D_1} is true:
< / p >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
< colgroup >
< col class = "org-right" / >
< col class = "org-right" / >
< / colgroup >
< tbody >
< tr >
< td class = "org-right" > 5< / td >
< td class = "org-right" > 0< / td >
< / tr >
2021-02-17 15:17:19 +01:00
< tr >
< td class = "org-right" > 0< / td >
< td class = "org-right" > 2< / 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 >
< 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 >
< 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 >
< 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 >
< 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 >
< 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 >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-orgad4e722" class = "outline-3" >
< h3 id = "orgad4e722" > < span class = "section-number-3" > 4.5< / span > Example 2 - Planar manipulator with 4 actuators< / h3 >
< div class = "outline-text-3" id = "text-4-5" >
2021-02-17 15:17:19 +01:00
< p >
2021-03-05 11:48:02 +01:00
Now consider the planar manipulator of Figure < a href = "#org1f0f00f" > 47< / a > .
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< div id = "org1f0f00f" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/model_planar_2.png" alt = "model_planar_2.png" / >
< / p >
2021-03-05 11:48:02 +01:00
< p > < span class = "figure-number" > Figure 47: < / span > Planar Manipulator< / p >
2021-02-17 15:17:19 +01:00
< / div >
< p >
The stiffnesses \(k_i\), the joint positions \({}^Mb_i\) and joint unit vectors \({}^M\hat{s}_i\) are defined below:
< / p >
< div class = "org-src-container" >
< 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]];
< / pre >
< / div >
< p >
Let’ s first verify that condition \eqref{eq:diag_cond_2D_1} is true:
< / 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" / >
< / 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 >
< 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 >
< 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 >
< 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 >
< 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 >
< 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 >
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-orga25e46d" class = "outline-2" >
< h2 id = "orga25e46d" > < span class = "section-number-2" > 5< / span > Diagonal Stiffness Matrix for a general parallel manipulator< / h2 >
< div class = "outline-text-2" id = "text-5" >
2021-02-17 15:17:19 +01:00
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-org53d94b5" class = "outline-3" >
< h3 id = "org53d94b5" > < span class = "section-number-3" > 5.1< / span > Model and Assumptions< / h3 >
< div class = "outline-text-3" id = "text-5-1" >
2021-02-17 15:17:19 +01:00
< 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-03-05 11:48:02 +01:00
An example is shown in Figure < a href = "#orgeae8638" > 48< / a > .
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< div id = "orgeae8638" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/stewart_architecture_example.png" alt = "stewart_architecture_example.png" / >
< / p >
2021-03-05 11:48:02 +01:00
< p > < span class = "figure-number" > Figure 48: < / span > Parallel manipulator Example< / p >
2021-02-17 15:17:19 +01:00
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-orgd2cf475" class = "outline-3" >
< h3 id = "orgd2cf475" > < span class = "section-number-3" > 5.2< / span > Objective< / h3 >
< div class = "outline-text-3" id = "text-5-2" >
2021-02-17 15:17:19 +01:00
< 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-03-05 11:48:02 +01:00
< div id = "outline-container-orgd9290b7" class = "outline-3" >
< h3 id = "orgd9290b7" > < span class = "section-number-3" > 5.3< / span > Analytical formula of the stiffness matrix< / h3 >
< div class = "outline-text-3" id = "text-5-3" >
2021-02-17 15:17:19 +01:00
< 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" >
< 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 >
< / ul >
< 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 (b_i \times \hat{s}_i) \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 >
As the vector cross product also can be expressed as the product of a skew-symmetric matrix and a vector, we obtain:
< / 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-03-05 11:48:02 +01:00
< div class = "note" id = "orgce3c3ff" >
2021-02-17 15:17:19 +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-03-05 11:48:02 +01:00
< div id = "outline-container-orgd0d0e45" class = "outline-3" >
< h3 id = "orgd0d0e45" > < span class = "section-number-3" > 5.4< / span > Example 1 - 6DoF manipulator (3D)< / h3 >
< div class = "outline-text-3" id = "text-5-4" >
2021-02-17 15:17:19 +01:00
< 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-03-05 11:48:02 +01:00
< div id = "outline-container-org32d660f" class = "outline-3" >
< h3 id = "org32d660f" > < span class = "section-number-3" > 5.5< / span > Example 2 - Stewart Platform< / h3 >
2021-02-17 15:17:19 +01:00
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-org659cc29" class = "outline-2" >
< h2 id = "org659cc29" > < span class = "section-number-2" > 6< / span > Stiffness and Mass Matrices in the Leg’ s frame< / h2 >
< div class = "outline-text-2" id = "text-6" >
2021-02-17 15:17:19 +01:00
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-org33194e0" class = "outline-3" >
< h3 id = "org33194e0" > < span class = "section-number-3" > 6.1< / span > Equations< / h3 >
< div class = "outline-text-3" id = "text-6-1" >
2021-02-17 15:17:19 +01:00
< p >
Equations in the \(\{M\}\) frame:
< / p >
\begin{equation}
\left( M_{\{M\}} s^2 + K_{\{M\}} \right) \mathcal{X}_{\{M\}} = \mathcal{F}_{\{M\}}
\end{equation}
< p >
Thank to the Jacobian, we can transform the equation of motion expressed in the \(\{M\}\) frame to the frame of the legs:
< / p >
\begin{equation}
J_{\{M\}}^{-T} \left( M_{\{M\}} s^2 + K_{\{M\}} \right) J_{\{M\}}^{-1} \dot{\mathcal{L}} = \tau
\end{equation}
< p >
And we have new stiffness and mass matrices:
< / p >
\begin{equation}
\left( M_{\{L\}} s^2 + K_{\{L\}} \right) \dot{\mathcal{L}} = \tau
\end{equation}
< p >
with:
< / p >
< ul class = "org-ul" >
< li > The local mass matrix:
\[ M_{\{L\}} = J_{\{M\}}^{-T} M_{\{M\}} J_{\{M\}}^{-1} \]< / li >
< li > The local stiffness matrix:
\[ K_{\{L\}} = J_{\{M\}}^{-T} K_{\{M\}} J_{\{M\}}^{-1} \]< / li >
< / ul >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-orgc3b8547" class = "outline-3" >
< h3 id = "orgc3b8547" > < span class = "section-number-3" > 6.2< / span > Stiffness matrix< / h3 >
< div class = "outline-text-3" id = "text-6-2" >
2021-02-17 15:17:19 +01:00
< p >
We have that:
\[ K_{\{M\}} = J_{\{M\}}^T \mathcal{K} J_{\{M\}} \]
< / p >
< p >
Therefore, we find that \(K_{\{L\}}\) is a diagonal matrix:
< / p >
\begin{equation}
K_{\{L\}} = \mathcal{K} = \begin{bmatrix}
k_1 & & 0 \\
& \ddots & \\
0 & & k_n
\end{bmatrix}
\end{equation}
< p >
The dynamics from \(\tau\) to \(\mathcal{L}\) is therefore decoupled at low frequency.
< / p >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-org18755e2" class = "outline-3" >
< h3 id = "org18755e2" > < span class = "section-number-3" > 6.3< / span > Mass matrix< / h3 >
< div class = "outline-text-3" id = "text-6-3" >
2021-02-17 15:17:19 +01:00
< p >
The mass matrix in the frames of the legs is:
\[ M_{\{L\}} = J_{\{M\}}^{-T} M_{\{M\}} J_{\{M\}}^{-1} \]
with \(M_{\{M\}}\) a diagonal matrix:
< / p >
\begin{equation}
M_{\{M\}} = \begin{bmatrix}
m & & & & & \\
& m & & & 0 & \\
& & m & & & \\
& & & I_x & & \\
& 0 & & & I_y & \\
& & & & & I_z
\end{bmatrix}
\end{equation}
< p >
Let’ s suppose \(M_{\{L\}} = \mathcal{M}\) diagonal and try to find what does this imply:
\[ M_{\{M\}} = J_{\{M\}}^{T} \mathcal{M} J_{\{M\}} \]
with:
< / p >
\begin{equation}
\mathcal{M} = \begin{bmatrix}
m_1 & & 0 \\
& \ddots & \\
0 & & m_n
\end{bmatrix}
\end{equation}
< p >
We obtain:
< / p >
\begin{equation}
\boxed{
M_{\{M\}} = \left[ \begin{array}{c|c}
m_i \hat{s}_i \hat{s}_i^T & m_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 & m_i (b_i \times \hat{s}_i) (b_i \times \hat{s}_i)^T
\end{array} \right]
}
\end{equation}
< p >
Therefore, we have the following conditions:
< / p >
\begin{align}
m_i \hat{s}_i \hat{s}_i^T & = m \bm{I}_{3} \\
m_i \hat{s}_i (b_i \times \hat{s}_i)^T & = \bm{O}_{3} \\
m_i (b_i \times \hat{s}_i) (b_i \times \hat{s}_i)^T & = \text{diag}(I_x, I_y, I_z)
\end{align}
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-org6f1a960" class = "outline-3" >
< h3 id = "org6f1a960" > < span class = "section-number-3" > 6.4< / span > Planar Example< / h3 >
< div class = "outline-text-3" id = "text-6-4" >
2021-02-17 15:17:19 +01:00
< p >
The stiffnesses \(k_i\), the joint positions \({}^Mb_i\) and joint unit vectors \({}^M\hat{s}_i\) are defined below:
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > ki = [1,1,1]; < 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],[< span class = "org-type" > -< / span > 10;< 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 >
< p >
Jacobian in frame \(\{M\}\):
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Jm = [si< 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 > ];
< / pre >
< / div >
< p >
And the stiffness matrix in frame \(\{K\}\):
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > Km = Jm< span class = "org-type" > '*< / span > diag(ki)< span class = "org-type" > *< / span > Jm;
< / 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" > 2< / td >
< td class = "org-right" > 0< / 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 >
< tr >
< td class = "org-right" > 1< / td >
< td class = "org-right" > -1< / td >
< td class = "org-right" > 2< / td >
< / tr >
< / tbody >
< / table >
< p >
Mass matrix in the frame \(\{M\}\):
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > m = 10; < span class = "org-comment" > % [kg]< / span >
I = 1; < span class = "org-comment" > % [kg.m^2]< / span >
Mm = diag([m, m, I]);
< / pre >
< / div >
< p >
Now compute \(K\) and \(M\) in the frame of the legs:
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > ML = inv(Jm)< span class = "org-type" > '*< / span > Mm< span class = "org-type" > *< / span > inv(Jm)
KL = inv(Jm)< 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" > Gm = 1< span class = "org-type" > /< / span > (ML< span class = "org-type" > *< / span > s< span class = "org-type" > ^< / span > 2 < span class = "org-type" > +< / span > KL);
< / pre >
< / div >
< div class = "org-src-container" >
< pre class = "src src-matlab" > freqs = logspace(< span class = "org-type" > -< / span > 2, 1, 1000);
< span class = "org-type" > figure< / span > ;
hold on;
< span class = "org-keyword" > for< / span > < span class = "org-variable-name" > < span class = "org-constant" > i< / span > < / span > = < span class = "org-constant" > 1:length(ki)< / span >
plot(freqs, abs(squeeze(freqresp(Gm(< span class = "org-constant" > i< / span > ,< span class = "org-constant" > i< / span > ), freqs, < span class = "org-string" > 'Hz'< / span > ))), < span class = "org-string" > 'k-'< / span > )
< span class = "org-keyword" > end< / span >
< span class = "org-keyword" > for< / span > < span class = "org-variable-name" > < span class = "org-constant" > i< / span > < / span > = < span class = "org-constant" > 1:length(ki)< / span >
< span class = "org-keyword" > for< / span > < span class = "org-variable-name" > < span class = "org-constant" > j< / span > < / span > = < span class = "org-constant" > < span class = "org-constant" > i< / span > < / span > < span class = "org-constant" > +1:length(ki)< / span >
plot(freqs, abs(squeeze(freqresp(Gm(< span class = "org-constant" > i< / span > ,< span class = "org-constant" > j< / span > ), freqs, < span class = "org-string" > 'Hz'< / span > ))), < span class = "org-string" > 'r-'< / span > )
< span class = "org-keyword" > end< / span >
< span class = "org-keyword" > end< / span >
hold off;
xlabel(< span class = "org-string" > 'Frequency [Hz]'< / span > );
ylabel(< span class = "org-string" > 'Magnitude'< / span > );
< span class = "org-type" > set< / span > (< span class = "org-variable-name" > gca< / span > , < span class = "org-string" > 'xscale'< / span > , < span class = "org-string" > 'log'< / span > );
< span class = "org-type" > set< / span > (< span class = "org-variable-name" > gca< / span > , < span class = "org-string" > 'yscale'< / span > , < span class = "org-string" > 'log'< / span > );
< / pre >
< / div >
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-org3dbf1cd" class = "outline-2" >
< h2 id = "org3dbf1cd" > < span class = "section-number-2" > 7< / span > Stewart Platform - Simscape Model< / h2 >
< div class = "outline-text-2" id = "text-7" >
2021-02-17 15:17:19 +01:00
< p >
2021-03-05 11:48:02 +01:00
< a id = "orgd344578" > < / a >
2021-02-17 15:17:19 +01:00
< / p >
< p >
2021-03-05 11:48:02 +01:00
In this analysis, we wish to applied SVD control to the Stewart Platform shown in Figure < a href = "#orged8bc20" > 49< / a > .
2021-02-17 15:17:19 +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-03-05 11:48:02 +01:00
< div id = "orged8bc20" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/SP_assembly.png" alt = "SP_assembly.png" / >
< / p >
2021-03-05 11:48:02 +01:00
< p > < span class = "figure-number" > Figure 49: < / span > Stewart Platform CAD View< / p >
2021-02-17 15:17:19 +01:00
< / 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-03-05 11:48:02 +01:00
< li > Section < a href = "#org99315d8" > 7.1< / a > : The parameters of the Simscape model of the Stewart platform are defined< / li >
< li > Section < a href = "#org9653aee" > 7.2< / a > : The plant is identified from the Simscape model and the system coupling is shown< / li >
< li > Section < a href = "#org6b33586" > 7.3< / a > : The plant is first decoupled using the Jacobian< / li >
< li > Section < a href = "#org0f841bf" > 7.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 = "#org82b4c89" > 7.5< / a > : The effectiveness of the decoupling with the Jacobian and SVD are compared using the Gershorin Radii< / li >
< li > Section < a href = "#orgb98aa14" > 7.6< / a > :< / li >
< li > Section < a href = "#org7f6bbdf" > 7.7< / a > : The dynamics of the decoupled plants are shown< / li >
< li > Section < a href = "#orgccfec9a" > 7.8< / a > : A diagonal controller is defined to control the decoupled plant< / li >
< li > Section < a href = "#orgc014338" > 7.9< / a > : Finally, the closed loop system properties are studied< / li >
2021-02-17 15:17:19 +01:00
< / ul >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-org4ad4383" class = "outline-3" >
< h3 id = "org4ad4383" > < span class = "section-number-3" > 7.1< / span > Simscape Model - Parameters< / h3 >
< div class = "outline-text-3" id = "text-7-1" >
2021-02-17 15:17:19 +01:00
< p >
2021-03-05 11:48:02 +01:00
< a id = "org99315d8" > < / a >
2021-02-17 15:17:19 +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-03-05 11:48:02 +01:00
< div id = "orgb204dfb" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/stewart_simscape.png" alt = "stewart_simscape.png" / >
< / p >
2021-03-05 11:48:02 +01:00
< p > < span class = "figure-number" > Figure 50: < / span > General view of the Simscape Model< / p >
2021-02-17 15:17:19 +01:00
< / div >
2021-03-05 11:48:02 +01:00
< div id = "org79ee500" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/stewart_platform_details.png" alt = "stewart_platform_details.png" / >
< / p >
2021-03-05 11:48:02 +01:00
< p > < span class = "figure-number" > Figure 51: < / span > Simscape model of the Stewart platform< / p >
2021-02-17 15:17:19 +01:00
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-orgf3900c8" class = "outline-3" >
< h3 id = "orgf3900c8" > < span class = "section-number-3" > 7.2< / span > Identification of the plant< / h3 >
< div class = "outline-text-3" id = "text-7-2" >
2021-02-17 15:17:19 +01:00
< p >
2021-03-05 11:48:02 +01:00
< a id = "org9653aee" > < / a >
2021-02-17 15:17:19 +01:00
< / p >
< p >
2021-03-05 11:48:02 +01:00
The plant shown in Figure < a href = "#orgf86f046" > 52< / a > is identified from the Simscape model.
2021-02-17 15:17:19 +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-03-05 11:48:02 +01:00
< div id = "orgf86f046" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/stewart_platform_plant.png" alt = "stewart_platform_plant.png" / >
< / p >
2021-03-05 11:48:02 +01:00
< p > < span class = "figure-number" > Figure 52: < / 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 >
2021-02-17 15:17:19 +01:00
< / 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-03-05 11:48:02 +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 = "#org2e138c6" > 53< / a > .
2021-02-17 15:17:19 +01:00
< / p >
< p >
One can easily see that the system is strongly coupled.
< / p >
2021-03-05 11:48:02 +01:00
< div id = "org2e138c6" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/stewart_platform_coupled_plant.png" alt = "stewart_platform_coupled_plant.png" / >
< / p >
2021-03-05 11:48:02 +01:00
< p > < span class = "figure-number" > Figure 53: < / span > Magnitude of all 36 elements of the transfer function matrix \(G_u\)< / p >
2021-02-17 15:17:19 +01:00
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-orgc9d7e64" class = "outline-3" >
< h3 id = "orgc9d7e64" > < span class = "section-number-3" > 7.3< / span > Decoupling using the Jacobian< / h3 >
< div class = "outline-text-3" id = "text-7-3" >
2021-02-17 15:17:19 +01:00
< p >
2021-03-05 11:48:02 +01:00
< a id = "org6b33586" > < / a >
Consider the control architecture shown in Figure < a href = "#org26d89f6" > 54< / a > .
2021-02-17 15:17:19 +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" >
2021-03-05 11:48:02 +01:00
< caption class = "t-above" > < span class = "table-number" > Table 16:< / span > Computed Jacobian Matrix< / caption >
2021-02-17 15:17:19 +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.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-03-05 11:48:02 +01:00
< div id = "org26d89f6" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/plant_decouple_jacobian.png" alt = "plant_decouple_jacobian.png" / >
< / p >
2021-03-05 11:48:02 +01:00
< p > < span class = "figure-number" > Figure 54: < / span > Decoupled plant \(\bm{G}_x\) using the Jacobian matrix \(J\)< / p >
2021-02-17 15:17:19 +01:00
< / 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-03-05 11:48:02 +01:00
< div id = "outline-container-org147009c" class = "outline-3" >
< h3 id = "org147009c" > < span class = "section-number-3" > 7.4< / span > Decoupling using the SVD< / h3 >
< div class = "outline-text-3" id = "text-7-4" >
2021-02-17 15:17:19 +01:00
< p >
2021-03-05 11:48:02 +01:00
< a id = "org0f841bf" > < / a >
2021-02-17 15:17:19 +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" >
2021-03-05 11:48:02 +01:00
< caption class = "t-above" > < span class = "table-number" > Table 17:< / span > Real approximate of \(G\) at the decoupling frequency \(\omega_c\)< / caption >
2021-02-17 15:17:19 +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 >
< p >
Note that the plant \(G_u\) at \(\omega_c\) is already an almost real matrix.
This can be seen on the Bode plots where the phase is close to 1.
This can be verified below where only the real value of \(G_u(\omega_c)\) is shown
< / p >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
2021-03-05 11:48:02 +01:00
< caption class = "t-above" > < span class = "table-number" > Table 18:< / span > Real part of \(G\) at the decoupling frequency \(\omega_c\)< / caption >
2021-02-17 15:17:19 +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 >
< p >
Now, the Singular Value Decomposition of \(H_1\) is performed:
\[ H_1 = U \Sigma V^H \]
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > [U,< span class = "org-type" > ~< / span > ,V] = svd(H1);
< / pre >
< / div >
< table border = "2" cellspacing = "0" cellpadding = "6" rules = "groups" frame = "hsides" >
2021-03-05 11:48:02 +01:00
< caption class = "t-above" > < span class = "table-number" > Table 19:< / span > Obtained matrix \(U\)< / caption >
2021-02-17 15:17:19 +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-03-05 11:48:02 +01:00
< caption class = "t-above" > < span class = "table-number" > Table 20:< / span > Obtained matrix \(V\)< / caption >
2021-02-17 15:17:19 +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 >
< p >
2021-03-05 11:48:02 +01:00
The obtained matrices \(U\) and \(V\) are used to decouple the system as shown in Figure < a href = "#orgaa8f61e" > 55< / a > .
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< div id = "orgaa8f61e" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/plant_decouple_svd.png" alt = "plant_decouple_svd.png" / >
< / p >
2021-03-05 11:48:02 +01:00
< p > < span class = "figure-number" > Figure 55: < / span > Decoupled plant \(\bm{G}_{SVD}\) using the Singular Value Decomposition< / p >
2021-02-17 15:17:19 +01:00
< / div >
< p >
The decoupled plant is then:
\[ G_{SVD}(s) = U^{-1} G_u(s) V^{-H} \]
< / p >
< div class = "org-src-container" >
< 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 > );
< / pre >
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-org78ebd1f" class = "outline-3" >
< h3 id = "org78ebd1f" > < span class = "section-number-3" > 7.5< / span > Verification of the decoupling using the “ Gershgorin Radii” < / h3 >
< div class = "outline-text-3" id = "text-7-5" >
2021-02-17 15:17:19 +01:00
< p >
2021-03-05 11:48:02 +01:00
< a id = "org82b4c89" > < / a >
2021-02-17 15:17:19 +01:00
< / p >
< 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 >
< 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 >
< p >
This is computed over the following frequencies.
< / p >
2021-03-05 11:48:02 +01:00
< div id = "orgb43f89e" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/simscape_model_gershgorin_radii.png" alt = "simscape_model_gershgorin_radii.png" / >
< / p >
2021-03-05 11:48:02 +01:00
< p > < span class = "figure-number" > Figure 56: < / span > Gershgorin Radii of the Coupled and Decoupled plants< / p >
2021-02-17 15:17:19 +01:00
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-orgf0afb6f" class = "outline-3" >
< h3 id = "orgf0afb6f" > < span class = "section-number-3" > 7.6< / span > Verification of the decoupling using the “ Relative Gain Array” < / h3 >
< div class = "outline-text-3" id = "text-7-6" >
2021-02-17 15:17:19 +01:00
< p >
2021-03-05 11:48:02 +01:00
< a id = "orgb98aa14" > < / a >
2021-02-17 15:17:19 +01:00
< / p >
< p >
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-03-05 11:48:02 +01:00
The obtained RGA elements are shown in Figure < a href = "#orgaaa187b" > 57< / a > .
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< div id = "orgaaa187b" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/simscape_model_rga.png" alt = "simscape_model_rga.png" / >
< / p >
2021-03-05 11:48:02 +01:00
< p > < span class = "figure-number" > Figure 57: < / span > Obtained norm of RGA elements for the SVD decoupled plant and the Jacobian decoupled plant< / p >
2021-02-17 15:17:19 +01:00
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-org23869f3" class = "outline-3" >
< h3 id = "org23869f3" > < span class = "section-number-3" > 7.7< / span > Obtained Decoupled Plants< / h3 >
< div class = "outline-text-3" id = "text-7-7" >
2021-02-17 15:17:19 +01:00
< p >
2021-03-05 11:48:02 +01:00
< a id = "org7f6bbdf" > < / a >
2021-02-17 15:17:19 +01:00
< / p >
< p >
2021-03-05 11:48:02 +01:00
The bode plot of the diagonal and off-diagonal elements of \(G_{SVD}\) are shown in Figure < a href = "#orgd314fce" > 58< / a > .
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< div id = "orgd314fce" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/simscape_model_decoupled_plant_svd.png" alt = "simscape_model_decoupled_plant_svd.png" / >
< / p >
2021-03-05 11:48:02 +01:00
< p > < span class = "figure-number" > Figure 58: < / span > Decoupled Plant using SVD< / p >
2021-02-17 15:17:19 +01:00
< / div >
< p >
2021-03-05 11:48:02 +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 = "#orgc115d38" > 59< / a > .
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< div id = "orgc115d38" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/simscape_model_decoupled_plant_jacobian.png" alt = "simscape_model_decoupled_plant_jacobian.png" / >
< / p >
2021-03-05 11:48:02 +01:00
< p > < span class = "figure-number" > Figure 59: < / 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 >
2021-02-17 15:17:19 +01:00
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-org265548f" class = "outline-3" >
< h3 id = "org265548f" > < span class = "section-number-3" > 7.8< / span > Diagonal Controller< / h3 >
< div class = "outline-text-3" id = "text-7-8" >
2021-02-17 15:17:19 +01:00
< p >
2021-03-05 11:48:02 +01:00
< a id = "orgccfec9a" > < / a >
The control diagram for the centralized control is shown in Figure < a href = "#orgb18d123" > 60< / a > .
2021-02-17 15:17:19 +01: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-03-05 11:48:02 +01:00
< div id = "orgb18d123" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/centralized_control.png" alt = "centralized_control.png" / >
< / p >
2021-03-05 11:48:02 +01:00
< p > < span class = "figure-number" > Figure 60: < / span > Control Diagram for the Centralized control< / p >
2021-02-17 15:17:19 +01:00
< / div >
< p >
2021-03-05 11:48:02 +01:00
The SVD control architecture is shown in Figure < a href = "#orgbf7e7f9" > 61< / a > .
2021-02-17 15:17:19 +01:00
The matrices \(U\) and \(V\) are used to decoupled the plant \(G\).
< / p >
2021-03-05 11:48:02 +01:00
< div id = "orgbf7e7f9" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/svd_control.png" alt = "svd_control.png" / >
< / p >
2021-03-05 11:48:02 +01:00
< p > < span class = "figure-number" > Figure 61: < / span > Control Diagram for the SVD control< / p >
2021-02-17 15:17:19 +01:00
< / div >
< p >
We choose the controller to be a low pass filter:
\[ K_c(s) = \frac{G_0}{1 + \frac{s}{\omega_0}} \]
< / p >
< 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 >
< 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 > 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 >
< / pre >
< / div >
< div class = "org-src-container" >
< 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]);
< / pre >
< / div >
< div class = "org-src-container" >
< 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]);
< / pre >
< / div >
< p >
2021-03-05 11:48:02 +01:00
The obtained diagonal elements of the loop gains are shown in Figure < a href = "#orgcd3ac90" > 62< / a > .
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< div id = "orgcd3ac90" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/stewart_comp_loop_gain_diagonal.png" alt = "stewart_comp_loop_gain_diagonal.png" / >
< / p >
2021-03-05 11:48:02 +01:00
< p > < span class = "figure-number" > Figure 62: < / span > Comparison of the diagonal elements of the loop gains for the SVD control architecture and the Jacobian one< / p >
2021-02-17 15:17:19 +01:00
< / div >
< / div >
< / div >
2021-03-05 11:48:02 +01:00
< div id = "outline-container-org1b19a6f" class = "outline-3" >
< h3 id = "org1b19a6f" > < span class = "section-number-3" > 7.9< / span > Closed-Loop system Performances< / h3 >
< div class = "outline-text-3" id = "text-7-9" >
2021-02-17 15:17:19 +01:00
< p >
2021-03-05 11:48:02 +01:00
< a id = "orgc014338" > < / a >
2021-02-17 15:17:19 +01:00
< / p >
< p >
Let’ s first verify the stability of the closed-loop systems:
< / p >
< div class = "org-src-container" >
< pre class = "src src-matlab" > isstable(G_cen)
< / pre >
< / div >
< pre class = "example" >
ans =
logical
1
< / pre >
< div class = "org-src-container" >
< pre class = "src src-matlab" > isstable(G_svd)
< / pre >
< / div >
< pre class = "example" >
ans =
logical
1
< / pre >
< p >
2021-03-05 11:48:02 +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 = "#orgb0102f5" > 63< / a > .
2021-02-17 15:17:19 +01:00
< / p >
2021-03-05 11:48:02 +01:00
< div id = "orgb0102f5" class = "figure" >
2021-02-17 15:17:19 +01:00
< p > < img src = "figs/stewart_platform_simscape_cl_transmissibility.png" alt = "stewart_platform_simscape_cl_transmissibility.png" / >
< / p >
2021-03-05 11:48:02 +01:00
< p > < span class = "figure-number" > Figure 63: < / span > Obtained Transmissibility< / p >
2021-02-17 15:17:19 +01:00
< / div >
< / div >
< / div >
< / div >
< / div >
< div id = "postamble" class = "status" >
< p class = "author" > Author: Dehaeze Thomas< / p >
2021-03-05 11:48:02 +01:00
< p class = "date" > Created: 2021-03-05 ven. 11:47< / p >
2021-02-17 15:17:19 +01:00
< / div >
< / body >
< / html >