nass-simscape/functions/index.html

884 lines
116 KiB
HTML
Raw Normal View History

2019-12-11 17:33:45 +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>
<!-- 2019-12-11 mer. 17:33 -->
<meta http-equiv="Content-Type" content="text/html;charset=utf-8" />
<meta name="viewport" content="width=device-width, initial-scale=1" />
<title>Matlab Functions used for the NASS Project</title>
<meta name="generator" content="Org mode" />
<meta name="author" content="Dehaeze Thomas" />
<style type="text/css">
<!--/*--><![CDATA[/*><!--*/
.title { text-align: center;
margin-bottom: .2em; }
.subtitle { text-align: center;
font-size: medium;
font-weight: bold;
margin-top:0; }
.todo { font-family: monospace; color: red; }
.done { font-family: monospace; color: green; }
.priority { font-family: monospace; color: orange; }
.tag { background-color: #eee; font-family: monospace;
padding: 2px; font-size: 80%; font-weight: normal; }
.timestamp { color: #bebebe; }
.timestamp-kwd { color: #5f9ea0; }
.org-right { margin-left: auto; margin-right: 0px; text-align: right; }
.org-left { margin-left: 0px; margin-right: auto; text-align: left; }
.org-center { margin-left: auto; margin-right: auto; text-align: center; }
.underline { text-decoration: underline; }
#postamble p, #preamble p { font-size: 90%; margin: .2em; }
p.verse { margin-left: 3%; }
pre {
border: 1px solid #ccc;
box-shadow: 3px 3px 3px #eee;
padding: 8pt;
font-family: monospace;
overflow: auto;
margin: 1.2em;
}
pre.src {
position: relative;
overflow: visible;
padding-top: 1.2em;
}
pre.src:before {
display: none;
position: absolute;
background-color: white;
top: -10px;
right: 10px;
padding: 3px;
border: 1px solid black;
}
pre.src:hover:before { display: inline;}
/* Languages per Org manual */
pre.src-asymptote:before { content: 'Asymptote'; }
pre.src-awk:before { content: 'Awk'; }
pre.src-C:before { content: 'C'; }
/* pre.src-C++ doesn't work in CSS */
pre.src-clojure:before { content: 'Clojure'; }
pre.src-css:before { content: 'CSS'; }
pre.src-D:before { content: 'D'; }
pre.src-ditaa:before { content: 'ditaa'; }
pre.src-dot:before { content: 'Graphviz'; }
pre.src-calc:before { content: 'Emacs Calc'; }
pre.src-emacs-lisp:before { content: 'Emacs Lisp'; }
pre.src-fortran:before { content: 'Fortran'; }
pre.src-gnuplot:before { content: 'gnuplot'; }
pre.src-haskell:before { content: 'Haskell'; }
pre.src-hledger:before { content: 'hledger'; }
pre.src-java:before { content: 'Java'; }
pre.src-js:before { content: 'Javascript'; }
pre.src-latex:before { content: 'LaTeX'; }
pre.src-ledger:before { content: 'Ledger'; }
pre.src-lisp:before { content: 'Lisp'; }
pre.src-lilypond:before { content: 'Lilypond'; }
pre.src-lua:before { content: 'Lua'; }
pre.src-matlab:before { content: 'MATLAB'; }
pre.src-mscgen:before { content: 'Mscgen'; }
pre.src-ocaml:before { content: 'Objective Caml'; }
pre.src-octave:before { content: 'Octave'; }
pre.src-org:before { content: 'Org mode'; }
pre.src-oz:before { content: 'OZ'; }
pre.src-plantuml:before { content: 'Plantuml'; }
pre.src-processing:before { content: 'Processing.js'; }
pre.src-python:before { content: 'Python'; }
pre.src-R:before { content: 'R'; }
pre.src-ruby:before { content: 'Ruby'; }
pre.src-sass:before { content: 'Sass'; }
pre.src-scheme:before { content: 'Scheme'; }
pre.src-screen:before { content: 'Gnu Screen'; }
pre.src-sed:before { content: 'Sed'; }
pre.src-sh:before { content: 'shell'; }
pre.src-sql:before { content: 'SQL'; }
pre.src-sqlite:before { content: 'SQLite'; }
/* additional languages in org.el's org-babel-load-languages alist */
pre.src-forth:before { content: 'Forth'; }
pre.src-io:before { content: 'IO'; }
pre.src-J:before { content: 'J'; }
pre.src-makefile:before { content: 'Makefile'; }
pre.src-maxima:before { content: 'Maxima'; }
pre.src-perl:before { content: 'Perl'; }
pre.src-picolisp:before { content: 'Pico Lisp'; }
pre.src-scala:before { content: 'Scala'; }
pre.src-shell:before { content: 'Shell Script'; }
pre.src-ebnf2ps:before { content: 'ebfn2ps'; }
/* additional language identifiers per "defun org-babel-execute"
in ob-*.el */
pre.src-cpp:before { content: 'C++'; }
pre.src-abc:before { content: 'ABC'; }
pre.src-coq:before { content: 'Coq'; }
pre.src-groovy:before { content: 'Groovy'; }
/* additional language identifiers from org-babel-shell-names in
ob-shell.el: ob-shell is the only babel language using a lambda to put
the execution function name together. */
pre.src-bash:before { content: 'bash'; }
pre.src-csh:before { content: 'csh'; }
pre.src-ash:before { content: 'ash'; }
pre.src-dash:before { content: 'dash'; }
pre.src-ksh:before { content: 'ksh'; }
pre.src-mksh:before { content: 'mksh'; }
pre.src-posh:before { content: 'posh'; }
/* Additional Emacs modes also supported by the LaTeX listings package */
pre.src-ada:before { content: 'Ada'; }
pre.src-asm:before { content: 'Assembler'; }
pre.src-caml:before { content: 'Caml'; }
pre.src-delphi:before { content: 'Delphi'; }
pre.src-html:before { content: 'HTML'; }
pre.src-idl:before { content: 'IDL'; }
pre.src-mercury:before { content: 'Mercury'; }
pre.src-metapost:before { content: 'MetaPost'; }
pre.src-modula-2:before { content: 'Modula-2'; }
pre.src-pascal:before { content: 'Pascal'; }
pre.src-ps:before { content: 'PostScript'; }
pre.src-prolog:before { content: 'Prolog'; }
pre.src-simula:before { content: 'Simula'; }
pre.src-tcl:before { content: 'tcl'; }
pre.src-tex:before { content: 'TeX'; }
pre.src-plain-tex:before { content: 'Plain TeX'; }
pre.src-verilog:before { content: 'Verilog'; }
pre.src-vhdl:before { content: 'VHDL'; }
pre.src-xml:before { content: 'XML'; }
pre.src-nxml:before { content: 'XML'; }
/* add a generic configuration mode; LaTeX export needs an additional
(add-to-list 'org-latex-listings-langs '(conf " ")) in .emacs */
pre.src-conf:before { content: 'Configuration File'; }
table { border-collapse:collapse; }
caption.t-above { caption-side: top; }
caption.t-bottom { caption-side: bottom; }
td, th { vertical-align:top; }
th.org-right { text-align: center; }
th.org-left { text-align: center; }
th.org-center { text-align: center; }
td.org-right { text-align: right; }
td.org-left { text-align: left; }
td.org-center { text-align: center; }
dt { font-weight: bold; }
.footpara { display: inline; }
.footdef { margin-bottom: 1em; }
.figure { padding: 1em; }
.figure p { text-align: center; }
.equation-container {
display: table;
text-align: center;
width: 100%;
}
.equation {
vertical-align: middle;
}
.equation-label {
display: table-cell;
text-align: right;
vertical-align: middle;
}
.inlinetask {
padding: 10px;
border: 2px solid gray;
margin: 10px;
background: #ffffcc;
}
#org-div-home-and-up
{ text-align: right; font-size: 70%; white-space: nowrap; }
textarea { overflow-x: auto; }
.linenr { font-size: smaller }
.code-highlighted { background-color: #ffff00; }
.org-info-js_info-navigation { border-style: none; }
#org-info-js_console-label
{ font-size: 10px; font-weight: bold; white-space: nowrap; }
.org-info-js_search-highlight
{ background-color: #ffff00; color: #000000; font-weight: bold; }
.org-svg { width: 90%; }
/*]]>*/-->
</style>
<link rel="stylesheet" type="text/css" href="../css/htmlize.css"/>
<link rel="stylesheet" type="text/css" href="../css/readtheorg.css"/>
<link rel="stylesheet" type="text/css" href="../css/zenburn.css"/>
<script type="text/javascript" src="../js/jquery.min.js"></script>
<script type="text/javascript" src="../js/bootstrap.min.js"></script>
<script type="text/javascript" src="../js/jquery.stickytableheaders.min.js"></script>
<script type="text/javascript" src="../js/readtheorg.js"></script>
<script type="text/javascript">
/*
@licstart The following is the entire license notice for the
JavaScript code in this tag.
Copyright (C) 2012-2019 Free Software Foundation, Inc.
The JavaScript code in this tag is free software: you can
redistribute it and/or modify it under the terms of the GNU
General Public License (GNU GPL) as published by the Free Software
Foundation, either version 3 of the License, or (at your option)
any later version. The code is distributed WITHOUT ANY WARRANTY;
without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU GPL for more details.
As additional permission under GNU GPL version 3 section 7, you
may distribute non-source (e.g., minimized or compacted) forms of
that code without the copy of the GNU GPL normally required by
section 4, provided you include this license notice and a URL
through which recipients can access the Corresponding Source.
@licend The above is the entire license notice
for the JavaScript code in this tag.
*/
<!--/*--><![CDATA[/*><!--*/
function CodeHighlightOn(elem, id)
{
var target = document.getElementById(id);
if(null != target) {
elem.cacheClassElem = elem.className;
elem.cacheClassTarget = target.className;
target.className = "code-highlighted";
elem.className = "code-highlighted";
}
}
function CodeHighlightOff(elem, id)
{
var target = document.getElementById(id);
if(elem.cacheClassElem)
elem.className = elem.cacheClassElem;
if(elem.cacheClassTarget)
target.className = elem.cacheClassTarget;
}
/*]]>*///-->
</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">Matlab Functions used for the NASS Project</h1>
<div id="table-of-contents">
<h2>Table of Contents</h2>
<div id="text-table-of-contents">
<ul>
<li><a href="#org05ce9cd">1. Functions</a>
<ul>
<li><a href="#orgd234316">1.1. computePsdDispl</a></li>
<li><a href="#orga7dcbe9">1.2. computeSetpoint</a></li>
<li><a href="#org38afc80">1.3. converErrorBasis</a></li>
<li><a href="#orge0e5103">1.4. generateDiagPidControl</a></li>
<li><a href="#orga0abbff">1.5. identifyPlant</a></li>
<li><a href="#orgd0e3a86">1.6. runSimulation</a></li>
<li><a href="#org288e05d">1.7. Inverse Kinematics of the Hexapod</a></li>
<li><a href="#org33a19ae">1.8. computeReferencePose</a></li>
</ul>
</li>
</ul>
</div>
</div>
<div id="outline-container-org05ce9cd" class="outline-2">
<h2 id="org05ce9cd"><span class="section-number-2">1</span> Functions</h2>
<div class="outline-text-2" id="text-1">
<p>
<a id="org1c061a7"></a>
</p>
</div>
<div id="outline-container-orgd234316" class="outline-3">
<h3 id="orgd234316"><span class="section-number-3">1.1</span> computePsdDispl</h3>
<div class="outline-text-3" id="text-1-1">
<p>
<a id="orgabe5453"></a>
</p>
<p>
This Matlab function is accessible <a href="../src/computePsdDispl.m">here</a>.
</p>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-keyword">function</span> <span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">[</span></span><span class="org-variable-name">psd_object</span><span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">]</span></span> = <span class="org-function-name">computePsdDispl</span><span class="org-rainbow-delimiters-depth-1">(</span><span class="org-variable-name">sys_data</span>, <span class="org-variable-name">t_init</span>, <span class="org-variable-name">n_av</span><span class="org-rainbow-delimiters-depth-1">)</span>
i_init = find<span class="org-rainbow-delimiters-depth-1">(</span>sys_data.time <span class="org-type">&gt;</span> t_init, <span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-1">)</span>;
han_win = hanning<span class="org-rainbow-delimiters-depth-1">(</span>ceil<span class="org-rainbow-delimiters-depth-2">(</span>length<span class="org-rainbow-delimiters-depth-3">(</span>sys_data.Dx<span class="org-rainbow-delimiters-depth-4">(</span>i_init<span class="org-type">:</span>end, <span class="org-type">:</span><span class="org-rainbow-delimiters-depth-4">)</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-type">/</span>n_av<span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
Fs = <span class="org-highlight-numbers-number">1</span><span class="org-type">/</span>sys_data.time<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-rainbow-delimiters-depth-1">[</span>pdx, f<span class="org-rainbow-delimiters-depth-1">]</span> = pwelch<span class="org-rainbow-delimiters-depth-1">(</span>sys_data.Dx<span class="org-rainbow-delimiters-depth-2">(</span>i_init<span class="org-type">:</span>end, <span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span>, han_win, <span class="org-rainbow-delimiters-depth-2">[]</span>, <span class="org-rainbow-delimiters-depth-2">[]</span>, Fs<span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-rainbow-delimiters-depth-1">[</span>pdy, <span class="org-type">~</span><span class="org-rainbow-delimiters-depth-1">]</span> = pwelch<span class="org-rainbow-delimiters-depth-1">(</span>sys_data.Dy<span class="org-rainbow-delimiters-depth-2">(</span>i_init<span class="org-type">:</span>end, <span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span>, han_win, <span class="org-rainbow-delimiters-depth-2">[]</span>, <span class="org-rainbow-delimiters-depth-2">[]</span>, Fs<span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-rainbow-delimiters-depth-1">[</span>pdz, <span class="org-type">~</span><span class="org-rainbow-delimiters-depth-1">]</span> = pwelch<span class="org-rainbow-delimiters-depth-1">(</span>sys_data.Dz<span class="org-rainbow-delimiters-depth-2">(</span>i_init<span class="org-type">:</span>end, <span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span>, han_win, <span class="org-rainbow-delimiters-depth-2">[]</span>, <span class="org-rainbow-delimiters-depth-2">[]</span>, Fs<span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-rainbow-delimiters-depth-1">[</span>prx, <span class="org-type">~</span><span class="org-rainbow-delimiters-depth-1">]</span> = pwelch<span class="org-rainbow-delimiters-depth-1">(</span>sys_data.Rx<span class="org-rainbow-delimiters-depth-2">(</span>i_init<span class="org-type">:</span>end, <span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span>, han_win, <span class="org-rainbow-delimiters-depth-2">[]</span>, <span class="org-rainbow-delimiters-depth-2">[]</span>, Fs<span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-rainbow-delimiters-depth-1">[</span>pry, <span class="org-type">~</span><span class="org-rainbow-delimiters-depth-1">]</span> = pwelch<span class="org-rainbow-delimiters-depth-1">(</span>sys_data.Ry<span class="org-rainbow-delimiters-depth-2">(</span>i_init<span class="org-type">:</span>end, <span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span>, han_win, <span class="org-rainbow-delimiters-depth-2">[]</span>, <span class="org-rainbow-delimiters-depth-2">[]</span>, Fs<span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-rainbow-delimiters-depth-1">[</span>prz, <span class="org-type">~</span><span class="org-rainbow-delimiters-depth-1">]</span> = pwelch<span class="org-rainbow-delimiters-depth-1">(</span>sys_data.Rz<span class="org-rainbow-delimiters-depth-2">(</span>i_init<span class="org-type">:</span>end, <span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span>, han_win, <span class="org-rainbow-delimiters-depth-2">[]</span>, <span class="org-rainbow-delimiters-depth-2">[]</span>, Fs<span class="org-rainbow-delimiters-depth-1">)</span>;
psd_object = struct<span class="org-rainbow-delimiters-depth-1">(</span>...
<span class="org-string">'f'</span>, f, ...
<span class="org-string">'dx'</span>, pdx, ...
<span class="org-string">'dy'</span>, pdy, ...
<span class="org-string">'dz'</span>, pdz, ...
<span class="org-string">'rx'</span>, prx, ...
<span class="org-string">'ry'</span>, pry, ...
<span class="org-string">'rz'</span>, prz<span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-keyword">end</span>
</pre>
</div>
</div>
</div>
<div id="outline-container-orga7dcbe9" class="outline-3">
<h3 id="orga7dcbe9"><span class="section-number-3">1.2</span> computeSetpoint</h3>
<div class="outline-text-3" id="text-1-2">
<p>
<a id="org879cac6"></a>
</p>
<p>
This Matlab function is accessible <a href="../src/computeSetpoint.m">here</a>.
</p>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-keyword">function</span> <span class="org-variable-name">setpoint</span> = <span class="org-function-name">computeSetpoint</span><span class="org-rainbow-delimiters-depth-1">(</span><span class="org-variable-name">ty</span>, <span class="org-variable-name">ry</span>, <span class="org-variable-name">rz</span><span class="org-rainbow-delimiters-depth-1">)</span>
<span class="org-matlab-cellbreak"><span class="org-comment">%%</span></span>
setpoint = zeros<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">6</span>, <span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Ty</span></span>
Ty = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> ;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span> ty ;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span> ;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-rainbow-delimiters-depth-1">]</span>;
% Tyinv = [<span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> ;
% <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span> <span class="org-type">-</span>ty ;
% <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span> ;
% <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> ];
<span class="org-matlab-cellbreak"><span class="org-comment">%% Ry</span></span>
Ry = <span class="org-rainbow-delimiters-depth-1">[</span> cos<span class="org-rainbow-delimiters-depth-2">(</span>ry<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span> sin<span class="org-rainbow-delimiters-depth-2">(</span>ry<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span> ;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> ;
<span class="org-type">-</span>sin<span class="org-rainbow-delimiters-depth-2">(</span>ry<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span> cos<span class="org-rainbow-delimiters-depth-2">(</span>ry<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span> ;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-rainbow-delimiters-depth-1">]</span>;
<span class="org-comment">% TMry = Ty*Ry*Tyinv;</span>
<span class="org-matlab-cellbreak"><span class="org-comment">%% Rz</span></span>
Rz = <span class="org-rainbow-delimiters-depth-1">[</span>cos<span class="org-rainbow-delimiters-depth-2">(</span>rz<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-type">-</span>sin<span class="org-rainbow-delimiters-depth-2">(</span>rz<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> ;
sin<span class="org-rainbow-delimiters-depth-2">(</span>rz<span class="org-rainbow-delimiters-depth-2">)</span> cos<span class="org-rainbow-delimiters-depth-2">(</span>rz<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> ;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span> ;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-rainbow-delimiters-depth-1">]</span>;
<span class="org-comment">% TMrz = Ty*TMry*Rz*TMry'*Tyinv;</span>
<span class="org-matlab-cellbreak"><span class="org-comment">%% All stages</span></span>
<span class="org-comment">% </span><span class="org-comment"><span class="org-constant">TM </span></span><span class="org-comment">= TMrz*TMry*Ty;</span>
TM = Ty<span class="org-type">*</span>Ry<span class="org-type">*</span>Rz;
<span class="org-rainbow-delimiters-depth-1">[</span>thetax, thetay, thetaz<span class="org-rainbow-delimiters-depth-1">]</span> = RM2angle<span class="org-rainbow-delimiters-depth-1">(</span>TM<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">1</span><span class="org-type">:</span><span class="org-highlight-numbers-number">3</span>, <span class="org-highlight-numbers-number">1</span><span class="org-type">:</span><span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
setpoint<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">1</span><span class="org-type">:</span><span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-1">)</span> = TM<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">1</span><span class="org-type">:</span><span class="org-highlight-numbers-number">3</span>, <span class="org-highlight-numbers-number">4</span><span class="org-rainbow-delimiters-depth-1">)</span>;
setpoint<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">4</span><span class="org-type">:</span><span class="org-highlight-numbers-number">6</span><span class="org-rainbow-delimiters-depth-1">)</span> = <span class="org-rainbow-delimiters-depth-1">[</span>thetax, thetay, thetaz<span class="org-rainbow-delimiters-depth-1">]</span>;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Custom Functions</span></span>
<span class="org-keyword">function</span> <span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">[</span></span><span class="org-variable-name">thetax, thetay, thetaz</span><span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">]</span></span> = <span class="org-function-name">RM2angle</span><span class="org-rainbow-delimiters-depth-1">(</span><span class="org-variable-name">R</span><span class="org-rainbow-delimiters-depth-1">)</span>
<span class="org-keyword">if</span> abs<span class="org-rainbow-delimiters-depth-1">(</span>abs<span class="org-rainbow-delimiters-depth-2">(</span>R<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">3</span>, <span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-type">-</span> <span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-1">)</span> <span class="org-type">&gt;</span> <span class="org-highlight-numbers-number">1e</span><span class="org-type">-</span><span class="org-highlight-numbers-number">6</span> % R31 <span class="org-type">!</span>= <span class="org-highlight-numbers-number">1</span> and R31 <span class="org-type">!</span>= <span class="org-type">-</span><span class="org-highlight-numbers-number">1</span>
thetay = <span class="org-type">-</span>asin<span class="org-rainbow-delimiters-depth-1">(</span>R<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">3</span>, <span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
thetax = atan2<span class="org-rainbow-delimiters-depth-1">(</span>R<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">3</span>, <span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">/</span>cos<span class="org-rainbow-delimiters-depth-2">(</span>thetay<span class="org-rainbow-delimiters-depth-2">)</span>, R<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">3</span>, <span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">/</span>cos<span class="org-rainbow-delimiters-depth-2">(</span>thetay<span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
thetaz = atan2<span class="org-rainbow-delimiters-depth-1">(</span>R<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">2</span>, <span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">/</span>cos<span class="org-rainbow-delimiters-depth-2">(</span>thetay<span class="org-rainbow-delimiters-depth-2">)</span>, R<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">1</span>, <span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">/</span>cos<span class="org-rainbow-delimiters-depth-2">(</span>thetay<span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-keyword">else</span>
thetaz = <span class="org-highlight-numbers-number">0</span>;
<span class="org-keyword">if</span> abs<span class="org-rainbow-delimiters-depth-1">(</span>R<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">3</span>, <span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">+</span><span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-1">)</span> <span class="org-type">&lt;</span> <span class="org-highlight-numbers-number">1e</span><span class="org-type">-</span><span class="org-highlight-numbers-number">6</span> % R31 = <span class="org-type">-</span><span class="org-highlight-numbers-number">1</span>
thetay = <span class="org-constant">pi</span><span class="org-type">/</span><span class="org-highlight-numbers-number">2</span>;
thetax = thetaz <span class="org-type">+</span> atan2<span class="org-rainbow-delimiters-depth-1">(</span>R<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">1</span>, <span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-2">)</span>, R<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">1</span>, <span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-keyword">else</span>
thetay = <span class="org-type">-</span><span class="org-constant">pi</span><span class="org-type">/</span><span class="org-highlight-numbers-number">2</span>;
thetax = <span class="org-type">-</span>thetaz <span class="org-type">+</span> atan2<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-type">-</span>R<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">1</span>, <span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-2">)</span>, <span class="org-type">-</span>R<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">1</span>, <span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-keyword">end</span>
<span class="org-keyword">end</span>
<span class="org-keyword">end</span>
<span class="org-keyword">end</span>
</pre>
</div>
</div>
</div>
<div id="outline-container-org38afc80" class="outline-3">
<h3 id="org38afc80"><span class="section-number-3">1.3</span> converErrorBasis</h3>
<div class="outline-text-3" id="text-1-3">
<p>
<a id="org1e357a7"></a>
</p>
<p>
This Matlab function is accessible <a href="../src/converErrorBasis.m">here</a>.
</p>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-keyword">function</span> <span class="org-variable-name">error_nass</span> = <span class="org-function-name">convertErrorBasis</span><span class="org-rainbow-delimiters-depth-1">(</span><span class="org-variable-name">pos</span>, <span class="org-variable-name">setpoint</span>, <span class="org-variable-name">ty</span>, <span class="org-variable-name">ry</span>, <span class="org-variable-name">rz</span><span class="org-rainbow-delimiters-depth-1">)</span>
<span class="org-comment">% convertErrorBasis -</span>
<span class="org-comment">%</span>
<span class="org-comment">% Syntax: convertErrorBasis(p_error, ty, ry, rz)</span>
<span class="org-comment">%</span>
<span class="org-comment">% Inputs:</span>
<span class="org-comment">% - p_error - Position error of the sample w.r.t. the granite [m, rad]</span>
<span class="org-comment">% - ty - Measured translation of the Ty stage [m]</span>
<span class="org-comment">% - ry - Measured rotation of the Ry stage [rad]</span>
<span class="org-comment">% - rz - Measured rotation of the Rz stage [rad]</span>
<span class="org-comment">%</span>
<span class="org-comment">% Outputs:</span>
<span class="org-comment">% - P_nass - Position error of the sample w.r.t. the NASS base [m]</span>
<span class="org-comment">% - R_nass - Rotation error of the sample w.r.t. the NASS base [rad]</span>
<span class="org-comment">%</span>
<span class="org-comment">% Example:</span>
<span class="org-comment">%</span>
<span class="org-matlab-cellbreak"><span class="org-comment">%% If line vector =&gt; column vector</span></span>
<span class="org-keyword">if</span> size<span class="org-rainbow-delimiters-depth-1">(</span>pos, <span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-1">)</span> <span class="org-type">==</span> <span class="org-highlight-numbers-number">6</span>
pos = pos<span class="org-type">'</span>;
<span class="org-keyword">end</span>
<span class="org-keyword">if</span> size<span class="org-rainbow-delimiters-depth-1">(</span>setpoint, <span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-1">)</span> <span class="org-type">==</span> <span class="org-highlight-numbers-number">6</span>
setpoint = setpoint<span class="org-type">'</span>;
<span class="org-keyword">end</span>
<span class="org-matlab-cellbreak"><span class="org-comment">%% Position of the sample in the frame fixed to the Granite</span></span>
P_granite = <span class="org-rainbow-delimiters-depth-1">[</span>pos<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">1</span><span class="org-type">:</span><span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-2">)</span>; <span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-1">]</span>; <span class="org-comment">% Position [m]</span>
R_granite = <span class="org-rainbow-delimiters-depth-1">[</span>setpoint<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">1</span><span class="org-type">:</span><span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-2">)</span>; <span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-1">]</span>; <span class="org-comment">% Reference [m]</span>
<span class="org-matlab-cellbreak"><span class="org-comment">%% Transformation matrices of the stages</span></span>
<span class="org-comment">% T-y</span>
TMty = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> ;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span> ty ;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span> ;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-rainbow-delimiters-depth-1">]</span>;
<span class="org-comment">% R-y</span>
TMry = <span class="org-rainbow-delimiters-depth-1">[</span> cos<span class="org-rainbow-delimiters-depth-2">(</span>ry<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span> sin<span class="org-rainbow-delimiters-depth-2">(</span>ry<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span> ;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> ;
<span class="org-type">-</span>sin<span class="org-rainbow-delimiters-depth-2">(</span>ry<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span> cos<span class="org-rainbow-delimiters-depth-2">(</span>ry<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span> ;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-rainbow-delimiters-depth-1">]</span>;
<span class="org-comment">% R-z</span>
TMrz = <span class="org-rainbow-delimiters-depth-1">[</span>cos<span class="org-rainbow-delimiters-depth-2">(</span>rz<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-type">-</span>sin<span class="org-rainbow-delimiters-depth-2">(</span>rz<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> ;
sin<span class="org-rainbow-delimiters-depth-2">(</span>rz<span class="org-rainbow-delimiters-depth-2">)</span> cos<span class="org-rainbow-delimiters-depth-2">(</span>rz<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> ;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span> ;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-rainbow-delimiters-depth-1">]</span>;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Compute Point coordinates in the new reference fixed to the NASS base</span></span>
<span class="org-comment">% P_nass = TMrz*TMry*TMty*P_granite;</span>
P_nass = TMrz<span class="org-type">\</span>TMry<span class="org-type">\</span>TMty<span class="org-type">\</span>P_granite;
R_nass = TMrz<span class="org-type">\</span>TMry<span class="org-type">\</span>TMty<span class="org-type">\</span>R_granite;
dx = R_nass<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-1">)</span><span class="org-type">-</span>P_nass<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-1">)</span>;
dy = R_nass<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-1">)</span><span class="org-type">-</span>P_nass<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-1">)</span>;
dz = R_nass<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-1">)</span><span class="org-type">-</span>P_nass<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Compute new basis vectors linked to the NASS base</span></span>
% ux_nass = TMrz<span class="org-type">*</span>TMry<span class="org-type">*</span>TMty<span class="org-type">*</span>[<span class="org-highlight-numbers-number">1</span>; <span class="org-highlight-numbers-number">0</span>; <span class="org-highlight-numbers-number">0</span>; <span class="org-highlight-numbers-number">0</span>];
% ux_nass = ux_nass(<span class="org-highlight-numbers-number">1</span><span class="org-type">:</span><span class="org-highlight-numbers-number">3</span>);
% uy_nass = TMrz<span class="org-type">*</span>TMry<span class="org-type">*</span>TMty<span class="org-type">*</span>[<span class="org-highlight-numbers-number">0</span>; <span class="org-highlight-numbers-number">1</span>; <span class="org-highlight-numbers-number">0</span>; <span class="org-highlight-numbers-number">0</span>];
% uy_nass = uy_nass(<span class="org-highlight-numbers-number">1</span><span class="org-type">:</span><span class="org-highlight-numbers-number">3</span>);
% uz_nass = TMrz<span class="org-type">*</span>TMry<span class="org-type">*</span>TMty<span class="org-type">*</span>[<span class="org-highlight-numbers-number">0</span>; <span class="org-highlight-numbers-number">0</span>; <span class="org-highlight-numbers-number">1</span>; <span class="org-highlight-numbers-number">0</span>];
% uz_nass = uz_nass(<span class="org-highlight-numbers-number">1</span><span class="org-type">:</span><span class="org-highlight-numbers-number">3</span>);
ux_nass = TMrz<span class="org-type">\</span>TMry<span class="org-type">\</span>TMty<span class="org-type">\</span><span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">1</span>; <span class="org-highlight-numbers-number">0</span>; <span class="org-highlight-numbers-number">0</span>; <span class="org-highlight-numbers-number">0</span><span class="org-rainbow-delimiters-depth-1">]</span>;
ux_nass = ux_nass<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">1</span><span class="org-type">:</span><span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-1">)</span>;
uy_nass = TMrz<span class="org-type">\</span>TMry<span class="org-type">\</span>TMty<span class="org-type">\</span><span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>; <span class="org-highlight-numbers-number">1</span>; <span class="org-highlight-numbers-number">0</span>; <span class="org-highlight-numbers-number">0</span><span class="org-rainbow-delimiters-depth-1">]</span>;
uy_nass = uy_nass<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">1</span><span class="org-type">:</span><span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-1">)</span>;
uz_nass = TMrz<span class="org-type">\</span>TMry<span class="org-type">\</span>TMty<span class="org-type">\</span><span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>; <span class="org-highlight-numbers-number">0</span>; <span class="org-highlight-numbers-number">1</span>; <span class="org-highlight-numbers-number">0</span><span class="org-rainbow-delimiters-depth-1">]</span>;
uz_nass = uz_nass<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">1</span><span class="org-type">:</span><span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Rotations error w.r.t. granite Frame</span></span>
<span class="org-comment">% Rotations error w.r.t. granite Frame</span>
rx_nass = pos<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">4</span><span class="org-rainbow-delimiters-depth-1">)</span>;
ry_nass = pos<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">5</span><span class="org-rainbow-delimiters-depth-1">)</span>;
rz_nass = pos<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">6</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-comment">% Rotation matrices of the Sample w.r.t. the Granite</span>
Mrx_error = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> ;
<span class="org-highlight-numbers-number">0</span> cos<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-type">-</span>rx_nass<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-type">-</span>sin<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-type">-</span>rx_nass<span class="org-rainbow-delimiters-depth-2">)</span> ;
<span class="org-highlight-numbers-number">0</span> sin<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-type">-</span>rx_nass<span class="org-rainbow-delimiters-depth-2">)</span> cos<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-type">-</span>rx_nass<span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">]</span>;
Mry_error = <span class="org-rainbow-delimiters-depth-1">[</span> cos<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-type">-</span>ry_nass<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span> sin<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-type">-</span>ry_nass<span class="org-rainbow-delimiters-depth-2">)</span> ;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span> ;
<span class="org-type">-</span>sin<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-type">-</span>ry_nass<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span> cos<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-type">-</span>ry_nass<span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">]</span>;
Mrz_error = <span class="org-rainbow-delimiters-depth-1">[</span>cos<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-type">-</span>rz_nass<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-type">-</span>sin<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-type">-</span>rz_nass<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span> ;
sin<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-type">-</span>rz_nass<span class="org-rainbow-delimiters-depth-2">)</span> cos<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-type">-</span>rz_nass<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span> ;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-1">]</span>;
<span class="org-comment">% Rotation matrix of the Sample w.r.t. the Granite</span>
Mr_error = Mrz_error<span class="org-type">*</span>Mry_error<span class="org-type">*</span>Mrx_error;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Use matrix to solve</span></span>
R = Mr_error<span class="org-type">/</span><span class="org-rainbow-delimiters-depth-1">[</span>ux_nass, uy_nass, uz_nass<span class="org-rainbow-delimiters-depth-1">]</span>; <span class="org-comment">% Rotation matrix from NASS base to Sample</span>
<span class="org-rainbow-delimiters-depth-1">[</span>thetax, thetay, thetaz<span class="org-rainbow-delimiters-depth-1">]</span> = RM2angle<span class="org-rainbow-delimiters-depth-1">(</span>R<span class="org-rainbow-delimiters-depth-1">)</span>;
error_nass = <span class="org-rainbow-delimiters-depth-1">[</span>dx; dy; dz; thetax; thetay; thetaz<span class="org-rainbow-delimiters-depth-1">]</span>;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Custom Functions</span></span>
<span class="org-keyword">function</span> <span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">[</span></span><span class="org-variable-name">thetax, thetay, thetaz</span><span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">]</span></span> = <span class="org-function-name">RM2angle</span><span class="org-rainbow-delimiters-depth-1">(</span><span class="org-variable-name">R</span><span class="org-rainbow-delimiters-depth-1">)</span>
<span class="org-keyword">if</span> abs<span class="org-rainbow-delimiters-depth-1">(</span>abs<span class="org-rainbow-delimiters-depth-2">(</span>R<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">3</span>, <span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-type">-</span> <span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-1">)</span> <span class="org-type">&gt;</span> <span class="org-highlight-numbers-number">1e</span><span class="org-type">-</span><span class="org-highlight-numbers-number">6</span> % R31 <span class="org-type">!</span>= <span class="org-highlight-numbers-number">1</span> and R31 <span class="org-type">!</span>= <span class="org-type">-</span><span class="org-highlight-numbers-number">1</span>
thetay = <span class="org-type">-</span>asin<span class="org-rainbow-delimiters-depth-1">(</span>R<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">3</span>, <span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-comment">% thetaybis = pi-thetay;</span>
thetax = atan2<span class="org-rainbow-delimiters-depth-1">(</span>R<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">3</span>, <span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">/</span>cos<span class="org-rainbow-delimiters-depth-2">(</span>thetay<span class="org-rainbow-delimiters-depth-2">)</span>, R<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">3</span>, <span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">/</span>cos<span class="org-rainbow-delimiters-depth-2">(</span>thetay<span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
% thetaxbis = atan2(R(<span class="org-highlight-numbers-number">3</span>, <span class="org-highlight-numbers-number">2</span>)<span class="org-type">/</span>cos(thetaybis), R(<span class="org-highlight-numbers-number">3</span>, <span class="org-highlight-numbers-number">3</span>)<span class="org-type">/</span>cos(thetaybis));
thetaz = atan2<span class="org-rainbow-delimiters-depth-1">(</span>R<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">2</span>, <span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">/</span>cos<span class="org-rainbow-delimiters-depth-2">(</span>thetay<span class="org-rainbow-delimiters-depth-2">)</span>, R<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">1</span>, <span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">/</span>cos<span class="org-rainbow-delimiters-depth-2">(</span>thetay<span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
% thetazbis = atan2(R(<span class="org-highlight-numbers-number">2</span>, <span class="org-highlight-numbers-number">1</span>)<span class="org-type">/</span>cos(thetaybis), R(<span class="org-highlight-numbers-number">1</span>, <span class="org-highlight-numbers-number">1</span>)<span class="org-type">/</span>cos(thetaybis));
<span class="org-keyword">else</span>
thetaz = <span class="org-highlight-numbers-number">0</span>;
<span class="org-keyword">if</span> abs<span class="org-rainbow-delimiters-depth-1">(</span>R<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">3</span>, <span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">+</span><span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-1">)</span> <span class="org-type">&lt;</span> <span class="org-highlight-numbers-number">1e</span><span class="org-type">-</span><span class="org-highlight-numbers-number">6</span> % R31 = <span class="org-type">-</span><span class="org-highlight-numbers-number">1</span>
thetay = <span class="org-constant">pi</span><span class="org-type">/</span><span class="org-highlight-numbers-number">2</span>;
thetax = thetaz <span class="org-type">+</span> atan2<span class="org-rainbow-delimiters-depth-1">(</span>R<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">1</span>, <span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-2">)</span>, R<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">1</span>, <span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-keyword">else</span>
thetay = <span class="org-type">-</span><span class="org-constant">pi</span><span class="org-type">/</span><span class="org-highlight-numbers-number">2</span>;
thetax = <span class="org-type">-</span>thetaz <span class="org-type">+</span> atan2<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-type">-</span>R<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">1</span>, <span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-2">)</span>, <span class="org-type">-</span>R<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">1</span>, <span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-keyword">end</span>
<span class="org-keyword">end</span>
<span class="org-keyword">end</span>
<span class="org-keyword">end</span>
</pre>
</div>
</div>
</div>
<div id="outline-container-orge0e5103" class="outline-3">
<h3 id="orge0e5103"><span class="section-number-3">1.4</span> generateDiagPidControl</h3>
<div class="outline-text-3" id="text-1-4">
<p>
<a id="org0799e34"></a>
</p>
<p>
This Matlab function is accessible <a href="../src/generateDiagPidControl.m">here</a>.
</p>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-keyword">function</span> <span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">[</span></span><span class="org-variable-name">K</span><span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">]</span></span> = <span class="org-function-name">generateDiagPidControl</span><span class="org-rainbow-delimiters-depth-1">(</span><span class="org-variable-name">G</span>, <span class="org-variable-name">fs</span><span class="org-rainbow-delimiters-depth-1">)</span>
<span class="org-matlab-cellbreak"><span class="org-comment">%%</span></span>
pid_opts = pidtuneOptions<span class="org-rainbow-delimiters-depth-1">(</span>...
<span class="org-string">'PhaseMargin'</span>, <span class="org-highlight-numbers-number">50</span>, ...
<span class="org-string">'DesignFocus'</span>, <span class="org-string">'disturbance-rejection'</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-matlab-cellbreak"><span class="org-comment">%%</span></span>
K = tf<span class="org-rainbow-delimiters-depth-1">(</span>zeros<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">6</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-keyword">for</span> <span class="org-variable-name"><span class="org-constant">i</span></span> = <span class="org-constant"><span class="org-highlight-numbers-number">1</span></span><span class="org-constant">:</span><span class="org-constant"><span class="org-highlight-numbers-number">6</span></span>
input_name = G.InputName<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-constant">i</span><span class="org-rainbow-delimiters-depth-1">)</span>;
output_name = G.OutputName<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-constant">i</span><span class="org-rainbow-delimiters-depth-1">)</span>;
K<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-constant">i</span>, <span class="org-constant">i</span><span class="org-rainbow-delimiters-depth-1">)</span> = tf<span class="org-rainbow-delimiters-depth-1">(</span>pidtune<span class="org-rainbow-delimiters-depth-2">(</span>minreal<span class="org-rainbow-delimiters-depth-3">(</span>G<span class="org-rainbow-delimiters-depth-4">(</span>output_name, input_name<span class="org-rainbow-delimiters-depth-4">)</span><span class="org-rainbow-delimiters-depth-3">)</span>, <span class="org-string">'PIDF'</span>, <span class="org-highlight-numbers-number">2</span><span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">*</span>fs, pid_opts<span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-keyword">end</span>
K.InputName = G.OutputName;
K.OutputName = G.InputName;
<span class="org-keyword">end</span>
</pre>
</div>
</div>
</div>
<div id="outline-container-orga0abbff" class="outline-3">
<h3 id="orga0abbff"><span class="section-number-3">1.5</span> identifyPlant</h3>
<div class="outline-text-3" id="text-1-5">
<p>
<a id="org348e5c9"></a>
</p>
<p>
This Matlab function is accessible <a href="../src/identifyPlant.m">here</a>.
</p>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-keyword">function</span> <span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">[</span></span><span class="org-variable-name">sys</span><span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">]</span></span> = <span class="org-function-name">identifyPlant</span><span class="org-rainbow-delimiters-depth-1">(</span><span class="org-variable-name">opts_param</span><span class="org-rainbow-delimiters-depth-1">)</span>
<span class="org-matlab-cellbreak"><span class="org-comment">%% Default values for opts</span></span>
opts = struct<span class="org-rainbow-delimiters-depth-1">()</span>;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Populate opts with input parameters</span></span>
<span class="org-keyword">if</span> exist<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'opts_param'</span>,<span class="org-string">'var'</span><span class="org-rainbow-delimiters-depth-1">)</span>
<span class="org-keyword">for</span> <span class="org-variable-name">opt</span> = <span class="org-constant">fieldnames</span><span class="org-constant"><span class="org-rainbow-delimiters-depth-1">(</span></span><span class="org-constant">opts_param</span><span class="org-constant"><span class="org-rainbow-delimiters-depth-1">)</span></span><span class="org-constant">'</span>
opts.<span class="org-rainbow-delimiters-depth-1">(</span>opt<span class="org-rainbow-delimiters-depth-2">{</span><span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-2">}</span><span class="org-rainbow-delimiters-depth-1">)</span> = opts_param.<span class="org-rainbow-delimiters-depth-1">(</span>opt<span class="org-rainbow-delimiters-depth-2">{</span><span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-2">}</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-keyword">end</span>
<span class="org-keyword">end</span>
<span class="org-matlab-cellbreak"><span class="org-comment">%% Options for Linearized</span></span>
options = linearizeOptions;
options.SampleTime = <span class="org-highlight-numbers-number">0</span>;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Name of the Simulink File</span></span>
mdl = <span class="org-string">'sim_nano_station_id'</span>;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Input/Output definition</span></span>
io<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-1">)</span> = linio<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-rainbow-delimiters-depth-2">[</span>mdl, <span class="org-string">'/Fn'</span><span class="org-rainbow-delimiters-depth-2">]</span>, <span class="org-highlight-numbers-number">1</span>, <span class="org-string">'input'</span><span class="org-rainbow-delimiters-depth-1">)</span>; <span class="org-comment">% Cartesian forces applied by NASS</span>
io<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-1">)</span> = linio<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-rainbow-delimiters-depth-2">[</span>mdl, <span class="org-string">'/Dw'</span><span class="org-rainbow-delimiters-depth-2">]</span>, <span class="org-highlight-numbers-number">1</span>, <span class="org-string">'input'</span><span class="org-rainbow-delimiters-depth-1">)</span>; <span class="org-comment">% Ground Motion</span>
io<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-1">)</span> = linio<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-rainbow-delimiters-depth-2">[</span>mdl, <span class="org-string">'/Fs'</span><span class="org-rainbow-delimiters-depth-2">]</span>, <span class="org-highlight-numbers-number">1</span>, <span class="org-string">'input'</span><span class="org-rainbow-delimiters-depth-1">)</span>; <span class="org-comment">% External forces on the sample</span>
io<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">4</span><span class="org-rainbow-delimiters-depth-1">)</span> = linio<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-rainbow-delimiters-depth-2">[</span>mdl, <span class="org-string">'/Fnl'</span><span class="org-rainbow-delimiters-depth-2">]</span>, <span class="org-highlight-numbers-number">1</span>, <span class="org-string">'input'</span><span class="org-rainbow-delimiters-depth-1">)</span>; <span class="org-comment">% Forces applied on the NASS's legs</span>
io<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">5</span><span class="org-rainbow-delimiters-depth-1">)</span> = linio<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-rainbow-delimiters-depth-2">[</span>mdl, <span class="org-string">'/Fd'</span><span class="org-rainbow-delimiters-depth-2">]</span>, <span class="org-highlight-numbers-number">1</span>, <span class="org-string">'input'</span><span class="org-rainbow-delimiters-depth-1">)</span>; <span class="org-comment">% Disturbance Forces</span>
io<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">6</span><span class="org-rainbow-delimiters-depth-1">)</span> = linio<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-rainbow-delimiters-depth-2">[</span>mdl, <span class="org-string">'/Dsm'</span><span class="org-rainbow-delimiters-depth-2">]</span>, <span class="org-highlight-numbers-number">1</span>, <span class="org-string">'output'</span><span class="org-rainbow-delimiters-depth-1">)</span>; <span class="org-comment">% Displacement of the sample</span>
io<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">7</span><span class="org-rainbow-delimiters-depth-1">)</span> = linio<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-rainbow-delimiters-depth-2">[</span>mdl, <span class="org-string">'/Fnlm'</span><span class="org-rainbow-delimiters-depth-2">]</span>, <span class="org-highlight-numbers-number">1</span>, <span class="org-string">'output'</span><span class="org-rainbow-delimiters-depth-1">)</span>; <span class="org-comment">% Force sensor in NASS's legs</span>
io<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">8</span><span class="org-rainbow-delimiters-depth-1">)</span> = linio<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-rainbow-delimiters-depth-2">[</span>mdl, <span class="org-string">'/Dnlm'</span><span class="org-rainbow-delimiters-depth-2">]</span>, <span class="org-highlight-numbers-number">1</span>, <span class="org-string">'output'</span><span class="org-rainbow-delimiters-depth-1">)</span>; <span class="org-comment">% Displacement of NASS's legs</span>
io<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">9</span><span class="org-rainbow-delimiters-depth-1">)</span> = linio<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-rainbow-delimiters-depth-2">[</span>mdl, <span class="org-string">'/Es'</span><span class="org-rainbow-delimiters-depth-2">]</span>, <span class="org-highlight-numbers-number">1</span>, <span class="org-string">'output'</span><span class="org-rainbow-delimiters-depth-1">)</span>; <span class="org-comment">% Position Error w.r.t. NASS base</span>
io<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">10</span><span class="org-rainbow-delimiters-depth-1">)</span> = linio<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-rainbow-delimiters-depth-2">[</span>mdl, <span class="org-string">'/Vlm'</span><span class="org-rainbow-delimiters-depth-2">]</span>, <span class="org-highlight-numbers-number">1</span>, <span class="org-string">'output'</span><span class="org-rainbow-delimiters-depth-1">)</span>; <span class="org-comment">% Measured absolute velocity of the legs</span>
<span class="org-matlab-cellbreak"><span class="org-comment">%% Run the linearization</span></span>
G = linearize<span class="org-rainbow-delimiters-depth-1">(</span>mdl, io, options<span class="org-rainbow-delimiters-depth-1">)</span>;
G.InputName = <span class="org-rainbow-delimiters-depth-1">{</span><span class="org-string">'Fnx'</span>, <span class="org-string">'Fny'</span>, <span class="org-string">'Fnz'</span>, <span class="org-string">'Mnx'</span>, <span class="org-string">'Mny'</span>, <span class="org-string">'Mnz'</span>, ...
<span class="org-string">'Dgx'</span>, <span class="org-string">'Dgy'</span>, <span class="org-string">'Dgz'</span>, ...
<span class="org-string">'Fsx'</span>, <span class="org-string">'Fsy'</span>, <span class="org-string">'Fsz'</span>, <span class="org-string">'Msx'</span>, <span class="org-string">'Msy'</span>, <span class="org-string">'Msz'</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-string">'Frzz'</span>, <span class="org-string">'Ftyx'</span>, <span class="org-string">'Ftyz'</span><span class="org-rainbow-delimiters-depth-1">}</span>;
G.OutputName = <span class="org-rainbow-delimiters-depth-1">{</span><span class="org-string">'Dx'</span>, <span class="org-string">'Dy'</span>, <span class="org-string">'Dz'</span>, <span class="org-string">'Rx'</span>, <span class="org-string">'Ry'</span>, <span class="org-string">'Rz'</span>, ...
<span class="org-string">'Fm1'</span>, <span class="org-string">'Fm2'</span>, <span class="org-string">'Fm3'</span>, <span class="org-string">'Fm4'</span>, <span class="org-string">'Fm5'</span>, <span class="org-string">'Fm6'</span>, ...
<span class="org-string">'Dm1'</span>, <span class="org-string">'Dm2'</span>, <span class="org-string">'Dm3'</span>, <span class="org-string">'Dm4'</span>, <span class="org-string">'Dm5'</span>, <span class="org-string">'Dm6'</span>, ...
<span class="org-string">'Edx'</span>, <span class="org-string">'Edy'</span>, <span class="org-string">'Edz'</span>, <span class="org-string">'Erx'</span>, <span class="org-string">'Ery'</span>, <span class="org-string">'Erz'</span>, ...
<span class="org-string">'Vm1'</span>, <span class="org-string">'Vm2'</span>, <span class="org-string">'Vm3'</span>, <span class="org-string">'Vm4'</span>, <span class="org-string">'Vm5'</span>, <span class="org-string">'Vm6'</span><span class="org-rainbow-delimiters-depth-1">}</span>;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Create the sub transfer functions</span></span>
minreal_tol = sqrt<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-constant">eps</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-comment">% From forces applied in the cartesian frame to displacement of the sample in the cartesian frame</span>
sys.G_cart = minreal<span class="org-rainbow-delimiters-depth-1">(</span>G<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-rainbow-delimiters-depth-3">{</span><span class="org-string">'Dx'</span>, <span class="org-string">'Dy'</span>, <span class="org-string">'Dz'</span>, <span class="org-string">'Rx'</span>, <span class="org-string">'Ry'</span>, <span class="org-string">'Rz'</span><span class="org-rainbow-delimiters-depth-3">}</span>, <span class="org-rainbow-delimiters-depth-3">{</span><span class="org-string">'Fnx'</span>, <span class="org-string">'Fny'</span>, <span class="org-string">'Fnz'</span>, <span class="org-string">'Mnx'</span>, <span class="org-string">'Mny'</span>, <span class="org-string">'Mnz'</span><span class="org-rainbow-delimiters-depth-3">}</span><span class="org-rainbow-delimiters-depth-2">)</span>, minreal_tol, <span class="org-constant">false</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-comment">% From ground motion to Sample displacement</span>
sys.G_gm = minreal<span class="org-rainbow-delimiters-depth-1">(</span>G<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-rainbow-delimiters-depth-3">{</span><span class="org-string">'Dx'</span>, <span class="org-string">'Dy'</span>, <span class="org-string">'Dz'</span>, <span class="org-string">'Rx'</span>, <span class="org-string">'Ry'</span>, <span class="org-string">'Rz'</span><span class="org-rainbow-delimiters-depth-3">}</span>, <span class="org-rainbow-delimiters-depth-3">{</span><span class="org-string">'Dgx'</span>, <span class="org-string">'Dgy'</span>, <span class="org-string">'Dgz'</span><span class="org-rainbow-delimiters-depth-3">}</span><span class="org-rainbow-delimiters-depth-2">)</span>, minreal_tol, <span class="org-constant">false</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-comment">% From direct forces applied on the sample to displacement of the sample</span>
sys.G_fs = minreal<span class="org-rainbow-delimiters-depth-1">(</span>G<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-rainbow-delimiters-depth-3">{</span><span class="org-string">'Dx'</span>, <span class="org-string">'Dy'</span>, <span class="org-string">'Dz'</span>, <span class="org-string">'Rx'</span>, <span class="org-string">'Ry'</span>, <span class="org-string">'Rz'</span><span class="org-rainbow-delimiters-depth-3">}</span>, <span class="org-rainbow-delimiters-depth-3">{</span><span class="org-string">'Fsx'</span>, <span class="org-string">'Fsy'</span>, <span class="org-string">'Fsz'</span>, <span class="org-string">'Msx'</span>, <span class="org-string">'Msy'</span>, <span class="org-string">'Msz'</span><span class="org-rainbow-delimiters-depth-3">}</span><span class="org-rainbow-delimiters-depth-2">)</span>, minreal_tol, <span class="org-constant">false</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-comment">% From forces applied on NASS's legs to force sensor in each leg</span>
sys.G_iff = minreal<span class="org-rainbow-delimiters-depth-1">(</span>G<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-rainbow-delimiters-depth-3">{</span><span class="org-string">'Fm1'</span>, <span class="org-string">'Fm2'</span>, <span class="org-string">'Fm3'</span>, <span class="org-string">'Fm4'</span>, <span class="org-string">'Fm5'</span>, <span class="org-string">'Fm6'</span><span class="org-rainbow-delimiters-depth-3">}</span>, <span class="org-rainbow-delimiters-depth-3">{</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-rainbow-delimiters-depth-3">}</span><span class="org-rainbow-delimiters-depth-2">)</span>, minreal_tol, <span class="org-constant">false</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-comment">% From forces applied on NASS's legs to displacement of each leg</span>
sys.G_dleg = minreal<span class="org-rainbow-delimiters-depth-1">(</span>G<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-rainbow-delimiters-depth-3">{</span><span class="org-string">'Dm1'</span>, <span class="org-string">'Dm2'</span>, <span class="org-string">'Dm3'</span>, <span class="org-string">'Dm4'</span>, <span class="org-string">'Dm5'</span>, <span class="org-string">'Dm6'</span><span class="org-rainbow-delimiters-depth-3">}</span>, <span class="org-rainbow-delimiters-depth-3">{</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-rainbow-delimiters-depth-3">}</span><span class="org-rainbow-delimiters-depth-2">)</span>, minreal_tol, <span class="org-constant">false</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-comment">% From forces/torques applied by the NASS to position error</span>
sys.G_plant = minreal<span class="org-rainbow-delimiters-depth-1">(</span>G<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-rainbow-delimiters-depth-3">{</span><span class="org-string">'Edx'</span>, <span class="org-string">'Edy'</span>, <span class="org-string">'Edz'</span>, <span class="org-string">'Erx'</span>, <span class="org-string">'Ery'</span>, <span class="org-string">'Erz'</span><span class="org-rainbow-delimiters-depth-3">}</span>, <span class="org-rainbow-delimiters-depth-3">{</span><span class="org-string">'Fnx'</span>, <span class="org-string">'Fny'</span>, <span class="org-string">'Fnz'</span>, <span class="org-string">'Mnx'</span>, <span class="org-string">'Mny'</span>, <span class="org-string">'Mnz'</span><span class="org-rainbow-delimiters-depth-3">}</span><span class="org-rainbow-delimiters-depth-2">)</span>, minreal_tol, <span class="org-constant">false</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-comment">% From forces/torques applied by the NASS to velocity of the actuator</span>
sys.G_geoph = minreal<span class="org-rainbow-delimiters-depth-1">(</span>G<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-rainbow-delimiters-depth-3">{</span><span class="org-string">'Vm1'</span>, <span class="org-string">'Vm2'</span>, <span class="org-string">'Vm3'</span>, <span class="org-string">'Vm4'</span>, <span class="org-string">'Vm5'</span>, <span class="org-string">'Vm6'</span><span class="org-rainbow-delimiters-depth-3">}</span>, <span class="org-rainbow-delimiters-depth-3">{</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-rainbow-delimiters-depth-3">}</span><span class="org-rainbow-delimiters-depth-2">)</span>, minreal_tol, <span class="org-constant">false</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-comment">% From various disturbance forces to position error</span>
sys.G_dist = minreal<span class="org-rainbow-delimiters-depth-1">(</span>G<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-rainbow-delimiters-depth-3">{</span><span class="org-string">'Dx'</span>, <span class="org-string">'Dy'</span>, <span class="org-string">'Dz'</span>, <span class="org-string">'Rx'</span>, <span class="org-string">'Ry'</span>, <span class="org-string">'Rz'</span><span class="org-rainbow-delimiters-depth-3">}</span>, <span class="org-rainbow-delimiters-depth-3">{</span><span class="org-string">'Frzz'</span>, <span class="org-string">'Ftyx'</span>, <span class="org-string">'Ftyz'</span><span class="org-rainbow-delimiters-depth-3">}</span><span class="org-rainbow-delimiters-depth-2">)</span>, minreal_tol, <span class="org-constant">false</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-matlab-cellbreak"><span class="org-comment">%% We remove low frequency and high frequency dynamics that are usually unstable</span></span>
<span class="org-comment">% using =freqsep= is risky as it may change the shape of the transfer functions</span>
% f_min = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">1</span>; % [Hz]
% f_max = <span class="org-highlight-numbers-number">1e4</span>; % [Hz]
% [<span class="org-type">~</span>, sys.G_cart] = freqsep(freqsep(sys.G_cart, <span class="org-highlight-numbers-number">2</span><span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">*</span>f_max), <span class="org-highlight-numbers-number">2</span><span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">*</span>f_min);
% [<span class="org-type">~</span>, sys.G_gm] = freqsep(freqsep(sys.G_gm, <span class="org-highlight-numbers-number">2</span><span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">*</span>f_max), <span class="org-highlight-numbers-number">2</span><span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">*</span>f_min);
% [<span class="org-type">~</span>, sys.G_fs] = freqsep(freqsep(sys.G_fs, <span class="org-highlight-numbers-number">2</span><span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">*</span>f_max), <span class="org-highlight-numbers-number">2</span><span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">*</span>f_min);
% [<span class="org-type">~</span>, sys.G_iff] = freqsep(freqsep(sys.G_iff, <span class="org-highlight-numbers-number">2</span><span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">*</span>f_max), <span class="org-highlight-numbers-number">2</span><span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">*</span>f_min);
% [<span class="org-type">~</span>, sys.G_dleg] = freqsep(freqsep(sys.G_dleg, <span class="org-highlight-numbers-number">2</span><span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">*</span>f_max), <span class="org-highlight-numbers-number">2</span><span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">*</span>f_min);
% [<span class="org-type">~</span>, sys.G_plant] = freqsep(freqsep(sys.G_plant, <span class="org-highlight-numbers-number">2</span><span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">*</span>f_max), <span class="org-highlight-numbers-number">2</span><span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">*</span>f_min);
<span class="org-matlab-cellbreak"><span class="org-comment">%% We finally verify that the system is stable</span></span>
<span class="org-keyword">if</span> <span class="org-type">~</span>isstable<span class="org-rainbow-delimiters-depth-1">(</span>sys.G_cart<span class="org-rainbow-delimiters-depth-1">)</span> <span class="org-type">||</span> <span class="org-type">~</span>isstable<span class="org-rainbow-delimiters-depth-1">(</span>sys.G_gm<span class="org-rainbow-delimiters-depth-1">)</span> <span class="org-type">||</span> <span class="org-type">~</span>isstable<span class="org-rainbow-delimiters-depth-1">(</span>sys.G_fs<span class="org-rainbow-delimiters-depth-1">)</span> <span class="org-type">||</span> <span class="org-type">~</span>isstable<span class="org-rainbow-delimiters-depth-1">(</span>sys.G_iff<span class="org-rainbow-delimiters-depth-1">)</span> <span class="org-type">||</span> <span class="org-type">~</span>isstable<span class="org-rainbow-delimiters-depth-1">(</span>sys.G_dleg<span class="org-rainbow-delimiters-depth-1">)</span> <span class="org-type">||</span> <span class="org-type">~</span>isstable<span class="org-rainbow-delimiters-depth-1">(</span>sys.G_plant<span class="org-rainbow-delimiters-depth-1">)</span>
warning<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'One of the identified system is unstable'</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-keyword">end</span>
<span class="org-keyword">end</span>
</pre>
</div>
</div>
</div>
<div id="outline-container-orgd0e3a86" class="outline-3">
<h3 id="orgd0e3a86"><span class="section-number-3">1.6</span> runSimulation</h3>
<div class="outline-text-3" id="text-1-6">
<p>
<a id="orgc58251f"></a>
</p>
<p>
This Matlab function is accessible <a href="../src/runSimulation.m">here</a>.
</p>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-keyword">function</span> <span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">[]</span></span> = <span class="org-function-name">runSimulation</span><span class="org-rainbow-delimiters-depth-1">(</span><span class="org-variable-name">sys_name</span>, <span class="org-variable-name">sys_mass</span>, <span class="org-variable-name">ctrl_type</span>, <span class="org-variable-name">act_damp</span><span class="org-rainbow-delimiters-depth-1">)</span>
<span class="org-matlab-cellbreak"><span class="org-comment">%% Load the controller and save it for the simulation</span></span>
<span class="org-keyword">if</span> strcmp<span class="org-rainbow-delimiters-depth-1">(</span>ctrl_type, <span class="org-string">'cl'</span><span class="org-rainbow-delimiters-depth-1">)</span> <span class="org-type">&amp;&amp;</span> strcmp<span class="org-rainbow-delimiters-depth-1">(</span>act_damp, <span class="org-string">'none'</span><span class="org-rainbow-delimiters-depth-1">)</span>
K_obj = load<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'./mat/K_fb.mat'</span><span class="org-rainbow-delimiters-depth-1">)</span>;
K = K_obj.<span class="org-rainbow-delimiters-depth-1">(</span>sprintf<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-string">'K_%s_%s'</span>, sys_mass, sys_name)); <span class="org-comment">%#</span><span class="org-comment"><span class="org-bold">ok</span></span>
save<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-string">'./mat/controllers.mat'</span>, <span class="org-string">'K'</span><span class="org-rainbow-delimiters-depth-3">)</span>;
<span class="org-keyword">elseif</span> strcmp<span class="org-rainbow-delimiters-depth-3">(</span>ctrl_type, <span class="org-string">'cl'</span><span class="org-rainbow-delimiters-depth-3">)</span> <span class="org-type">&amp;&amp;</span> strcmp<span class="org-rainbow-delimiters-depth-3">(</span>act_damp, <span class="org-string">'iff'</span><span class="org-rainbow-delimiters-depth-3">)</span>
K_obj = load<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-string">'./mat/K_fb_iff.mat'</span><span class="org-rainbow-delimiters-depth-3">)</span>;
K = K_obj.<span class="org-rainbow-delimiters-depth-3">(</span>sprintf<span class="org-rainbow-delimiters-depth-4">(</span><span class="org-string">'K_%s_%s_iff'</span>, sys_mass, sys_name)); <span class="org-comment">%#</span><span class="org-comment"><span class="org-bold">ok</span></span>
save<span class="org-rainbow-delimiters-depth-5">(</span><span class="org-string">'./mat/controllers.mat'</span>, <span class="org-string">'K'</span><span class="org-rainbow-delimiters-depth-5">)</span>;
<span class="org-keyword">elseif</span> strcmp<span class="org-rainbow-delimiters-depth-5">(</span>ctrl_type, <span class="org-string">'ol'</span><span class="org-rainbow-delimiters-depth-5">)</span>
K = tf<span class="org-rainbow-delimiters-depth-5">(</span>zeros<span class="org-rainbow-delimiters-depth-6">(</span><span class="org-highlight-numbers-number">6</span><span class="org-rainbow-delimiters-depth-6">)</span><span class="org-rainbow-delimiters-depth-5">)</span>; <span class="org-comment">%#</span><span class="org-comment"><span class="org-bold">ok</span></span>
save<span class="org-rainbow-delimiters-depth-5">(</span><span class="org-string">'./mat/controllers.mat'</span>, <span class="org-string">'K'</span><span class="org-rainbow-delimiters-depth-5">)</span>;
<span class="org-keyword">else</span>
error<span class="org-rainbow-delimiters-depth-5">(</span><span class="org-string">'ctrl_type should be cl or ol'</span><span class="org-rainbow-delimiters-depth-5">)</span>;
<span class="org-keyword">end</span>
<span class="org-matlab-cellbreak"><span class="org-comment">%% Active Damping</span></span>
<span class="org-keyword">if</span> strcmp<span class="org-rainbow-delimiters-depth-5">(</span>act_damp, <span class="org-string">'iff'</span><span class="org-rainbow-delimiters-depth-5">)</span>
K_iff_crit = load<span class="org-rainbow-delimiters-depth-5">(</span><span class="org-string">'./mat/K_iff_crit.mat'</span><span class="org-rainbow-delimiters-depth-5">)</span>;
K_iff = K_iff_crit.<span class="org-rainbow-delimiters-depth-5">(</span>sprintf<span class="org-rainbow-delimiters-depth-6">(</span><span class="org-string">'K_iff_%s_%s'</span>, sys_mass, sys_name)); <span class="org-comment">%#</span><span class="org-comment"><span class="org-bold">ok</span></span>
save<span class="org-rainbow-delimiters-depth-7">(</span><span class="org-string">'./mat/controllers.mat'</span>, <span class="org-string">'K_iff'</span>, <span class="org-string">'-append'</span><span class="org-rainbow-delimiters-depth-7">)</span>;
<span class="org-keyword">elseif</span> strcmp<span class="org-rainbow-delimiters-depth-7">(</span>act_damp, <span class="org-string">'none'</span><span class="org-rainbow-delimiters-depth-7">)</span>
K_iff = tf<span class="org-rainbow-delimiters-depth-7">(</span>zeros<span class="org-rainbow-delimiters-depth-8">(</span><span class="org-highlight-numbers-number">6</span><span class="org-rainbow-delimiters-depth-8">)</span><span class="org-rainbow-delimiters-depth-7">)</span>; <span class="org-comment">%#</span><span class="org-comment"><span class="org-bold">ok</span></span>
save<span class="org-rainbow-delimiters-depth-7">(</span><span class="org-string">'./mat/controllers.mat'</span>, <span class="org-string">'K_iff'</span>, <span class="org-string">'-append'</span><span class="org-rainbow-delimiters-depth-7">)</span>;
<span class="org-keyword">end</span>
<span class="org-matlab-cellbreak"><span class="org-comment">%%</span></span>
<span class="org-keyword">if</span> strcmp<span class="org-rainbow-delimiters-depth-7">(</span>sys_name, <span class="org-string">'pz'</span><span class="org-rainbow-delimiters-depth-7">)</span>
initializeNanoHexapod<span class="org-rainbow-delimiters-depth-7">(</span>struct<span class="org-rainbow-delimiters-depth-8">(</span><span class="org-string">'actuator'</span>, <span class="org-string">'piezo'</span><span class="org-rainbow-delimiters-depth-8">)</span><span class="org-rainbow-delimiters-depth-7">)</span>;
<span class="org-keyword">elseif</span> strcmp<span class="org-rainbow-delimiters-depth-7">(</span>sys_name, <span class="org-string">'vc'</span><span class="org-rainbow-delimiters-depth-7">)</span>
initializeNanoHexapod<span class="org-rainbow-delimiters-depth-7">(</span>struct<span class="org-rainbow-delimiters-depth-8">(</span><span class="org-string">'actuator'</span>, <span class="org-string">'lorentz'</span><span class="org-rainbow-delimiters-depth-8">)</span><span class="org-rainbow-delimiters-depth-7">)</span>;
<span class="org-keyword">else</span>
error<span class="org-rainbow-delimiters-depth-7">(</span><span class="org-string">'sys_name should be pz or vc'</span><span class="org-rainbow-delimiters-depth-7">)</span>;
<span class="org-keyword">end</span>
<span class="org-keyword">if</span> strcmp<span class="org-rainbow-delimiters-depth-7">(</span>sys_mass, <span class="org-string">'light'</span><span class="org-rainbow-delimiters-depth-7">)</span>
initializeSample<span class="org-rainbow-delimiters-depth-7">(</span>struct<span class="org-rainbow-delimiters-depth-8">(</span><span class="org-string">'mass'</span>, <span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-8">)</span><span class="org-rainbow-delimiters-depth-7">)</span>;
<span class="org-keyword">elseif</span> strcmp<span class="org-rainbow-delimiters-depth-7">(</span>sys_mass, <span class="org-string">'heavy'</span><span class="org-rainbow-delimiters-depth-7">)</span>
initializeSample<span class="org-rainbow-delimiters-depth-7">(</span>struct<span class="org-rainbow-delimiters-depth-8">(</span><span class="org-string">'mass'</span>, <span class="org-highlight-numbers-number">50</span><span class="org-rainbow-delimiters-depth-8">)</span><span class="org-rainbow-delimiters-depth-7">)</span>;
<span class="org-keyword">else</span>
error<span class="org-rainbow-delimiters-depth-7">(</span><span class="org-string">'sys_mass should be light or heavy'</span><span class="org-rainbow-delimiters-depth-7">)</span>;
<span class="org-keyword">end</span>
<span class="org-matlab-cellbreak"><span class="org-comment">%% Run the simulation</span></span>
<span class="org-matlab-simulink-keyword">sim</span><span class="org-rainbow-delimiters-depth-7">(</span><span class="org-string">'sim_nano_station_ctrl.slx'</span><span class="org-rainbow-delimiters-depth-7">)</span>;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Split the Dsample matrix into vectors</span></span>
<span class="org-rainbow-delimiters-depth-7">[</span>Dx, Dy, Dz, Rx, Ry, Rz<span class="org-rainbow-delimiters-depth-7">]</span> = matSplit<span class="org-rainbow-delimiters-depth-7">(</span>Es.Data, <span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-7">)</span>; <span class="org-comment">%#</span><span class="org-comment"><span class="org-bold">ok</span></span>
time = Dsample.Time; <span class="org-comment">%#</span><span class="org-comment"><span class="org-bold">ok</span></span>
<span class="org-matlab-cellbreak"><span class="org-comment">%% Save the result</span></span>
filename = sprintf<span class="org-rainbow-delimiters-depth-7">(</span><span class="org-string">'sim_%s_%s_%s_%s'</span>, sys_mass, sys_name, ctrl_type, act_damp);
save<span class="org-rainbow-delimiters-depth-8">(</span>sprintf<span class="org-rainbow-delimiters-depth-9">(</span><span class="org-string">'./mat/%s.mat'</span>, filename), ...
<span class="org-string">'time'</span>, <span class="org-string">'Dx'</span>, <span class="org-string">'Dy'</span>, <span class="org-string">'Dz'</span>, <span class="org-string">'Rx'</span>, <span class="org-string">'Ry'</span>, <span class="org-string">'Rz'</span>, <span class="org-string">'K'</span><span class="org-rainbow-delimiters-depth-9">)</span>;
<span class="org-keyword">end</span>
</pre>
</div>
</div>
</div>
<div id="outline-container-org288e05d" class="outline-3">
<h3 id="org288e05d"><span class="section-number-3">1.7</span> Inverse Kinematics of the Hexapod</h3>
<div class="outline-text-3" id="text-1-7">
<p>
<a id="orgd4c4eda"></a>
</p>
<p>
This Matlab function is accessible <a href="src/inverseKinematicsHexapod.m">here</a>.
</p>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-keyword">function</span> <span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">[</span></span><span class="org-variable-name">L</span><span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">]</span></span> = <span class="org-function-name">inverseKinematicsHexapod</span><span class="org-rainbow-delimiters-depth-1">(</span><span class="org-variable-name">hexapod</span>, <span class="org-variable-name">AP</span>, <span class="org-variable-name">ARB</span><span class="org-rainbow-delimiters-depth-1">)</span>
<span class="org-comment">% inverseKinematicsHexapod - Compute the initial position of each leg to have the wanted Hexapod's position</span>
<span class="org-comment">%</span>
<span class="org-comment">% Syntax: inverseKinematicsHexapod(hexapod, AP, ARB)</span>
<span class="org-comment">%</span>
<span class="org-comment">% Inputs:</span>
<span class="org-comment">% - hexapod - Hexapod object containing the geometry of the hexapod</span>
<span class="org-comment">% - AP - Position vector of point OB expressed in frame {A} in [m]</span>
<span class="org-comment">% - ARB - Rotation Matrix expressed in frame {A}</span>
<span class="org-comment">% Wanted Length of the hexapod's legs [m]</span>
L = zeros<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">6</span>, <span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-keyword">for</span> <span class="org-variable-name"><span class="org-constant">i</span></span> = <span class="org-constant"><span class="org-highlight-numbers-number">1</span></span><span class="org-constant">:length</span><span class="org-constant"><span class="org-rainbow-delimiters-depth-1">(</span></span><span class="org-constant">L</span><span class="org-constant"><span class="org-rainbow-delimiters-depth-1">)</span></span>
Bbi = hexapod.pos_top_tranform<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-constant">i</span>, <span class="org-type">:</span><span class="org-rainbow-delimiters-depth-1">)</span><span class="org-type">'</span> <span class="org-type">-</span> <span class="org-highlight-numbers-number">1e</span><span class="org-type">-</span><span class="org-highlight-numbers-number">3</span><span class="org-type">*</span><span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span> ; <span class="org-highlight-numbers-number">0</span> ; hexapod.TP.thickness<span class="org-type">+</span>hexapod.Leg.sphere.top<span class="org-type">+</span>hexapod.SP.thickness.top<span class="org-type">+</span>hexapod.jacobian<span class="org-rainbow-delimiters-depth-1">]</span>; <span class="org-comment">% [m]</span>
Aai = hexapod.pos_base<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-constant">i</span>, <span class="org-type">:</span><span class="org-rainbow-delimiters-depth-1">)</span><span class="org-type">'</span> <span class="org-type">+</span> <span class="org-highlight-numbers-number">1e</span><span class="org-type">-</span><span class="org-highlight-numbers-number">3</span><span class="org-type">*</span><span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span> ; <span class="org-highlight-numbers-number">0</span> ; hexapod.BP.thickness<span class="org-type">+</span>hexapod.Leg.sphere.bottom<span class="org-type">+</span>hexapod.SP.thickness.bottom<span class="org-type">-</span>hexapod.h<span class="org-type">-</span>hexapod.jacobian<span class="org-rainbow-delimiters-depth-1">]</span>; <span class="org-comment">% [m]</span>
L<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-constant">i</span><span class="org-rainbow-delimiters-depth-1">)</span> = sqrt<span class="org-rainbow-delimiters-depth-1">(</span>AP<span class="org-type">'*</span>AP <span class="org-type">+</span> Bbi<span class="org-type">'*</span>Bbi <span class="org-type">+</span> Aai<span class="org-type">'*</span>Aai <span class="org-type">-</span> <span class="org-highlight-numbers-number">2</span><span class="org-type">*</span>AP<span class="org-type">'*</span>Aai <span class="org-type">+</span> <span class="org-highlight-numbers-number">2</span><span class="org-type">*</span>AP<span class="org-type">'*</span><span class="org-rainbow-delimiters-depth-2">(</span>ARB<span class="org-type">*</span>Bbi<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-type">-</span> <span class="org-highlight-numbers-number">2</span><span class="org-type">*</span><span class="org-rainbow-delimiters-depth-2">(</span>ARB<span class="org-type">*</span>Bbi<span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">'*</span>Aai<span class="org-rainbow-delimiters-depth-1">)</span>;
<span class="org-keyword">end</span>
<span class="org-keyword">end</span>
</pre>
</div>
</div>
</div>
<div id="outline-container-org33a19ae" class="outline-3">
<h3 id="org33a19ae"><span class="section-number-3">1.8</span> computeReferencePose</h3>
<div class="outline-text-3" id="text-1-8">
<p>
<a id="org14f924b"></a>
</p>
<p>
This Matlab function is accessible <a href="src/computeReferencePose.m">here</a>.
</p>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-keyword">function</span> <span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">[</span></span><span class="org-variable-name">WTr</span><span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">]</span></span> = <span class="org-function-name">computeReferencePose</span><span class="org-rainbow-delimiters-depth-1">(</span><span class="org-variable-name">Dy</span>, <span class="org-variable-name">Ry</span>, <span class="org-variable-name">Rz</span>, <span class="org-variable-name">Dh</span>, <span class="org-variable-name">Dn</span><span class="org-rainbow-delimiters-depth-1">)</span>
<span class="org-comment">% computeReferencePose - Compute the homogeneous transformation matrix corresponding to the wanted pose of the sample</span>
<span class="org-comment">%</span>
<span class="org-comment">% Syntax: [WTr] = computeReferencePose(Dy, Ry, Rz, Dh, Dn)</span>
<span class="org-comment">%</span>
<span class="org-comment">% Inputs:</span>
<span class="org-comment">% - Dy - Reference of the Translation Stage [m]</span>
<span class="org-comment">% - Ry - Reference of the Tilt Stage [rad]</span>
<span class="org-comment">% - Rz - Reference of the Spindle [rad]</span>
<span class="org-comment">% - Dh - Reference of the Micro Hexapod (Pitch, Roll, Yaw angles) [m, m, m, rad, rad, rad]</span>
<span class="org-comment">% - Dn - Reference of the Nano Hexapod [m, m, m, rad, rad, rad]</span>
<span class="org-comment">%</span>
<span class="org-comment">% Outputs:</span>
<span class="org-comment">% - WTr -</span>
<span class="org-matlab-cellbreak"><span class="org-comment">%% Translation Stage</span></span>
Rty = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span>;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span> Dy;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span>;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-1">]</span>;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Tilt Stage - Pure rotating aligned with Ob</span></span>
Rry = <span class="org-rainbow-delimiters-depth-1">[</span> cos<span class="org-rainbow-delimiters-depth-2">(</span>Ry<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span> sin<span class="org-rainbow-delimiters-depth-2">(</span>Ry<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span>;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span>;
<span class="org-type">-</span>sin<span class="org-rainbow-delimiters-depth-2">(</span>Ry<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span> cos<span class="org-rainbow-delimiters-depth-2">(</span>Ry<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span>;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-1">]</span>;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Spindle - Rotation along the Z axis</span></span>
Rrz = <span class="org-rainbow-delimiters-depth-1">[</span>cos<span class="org-rainbow-delimiters-depth-2">(</span>Rz<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-type">-</span>sin<span class="org-rainbow-delimiters-depth-2">(</span>Rz<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> ;
sin<span class="org-rainbow-delimiters-depth-2">(</span>Rz<span class="org-rainbow-delimiters-depth-2">)</span> cos<span class="org-rainbow-delimiters-depth-2">(</span>Rz<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> ;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span> ;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-rainbow-delimiters-depth-1">]</span>;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Micro-Hexapod</span></span>
Rhx = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span>;
<span class="org-highlight-numbers-number">0</span> cos<span class="org-rainbow-delimiters-depth-2">(</span>Dh<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">4</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-type">-</span>sin<span class="org-rainbow-delimiters-depth-2">(</span>Dh<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">4</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span>;
<span class="org-highlight-numbers-number">0</span> sin<span class="org-rainbow-delimiters-depth-2">(</span>Dh<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">4</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span> cos<span class="org-rainbow-delimiters-depth-2">(</span>Dh<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">4</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">]</span>;
Rhy = <span class="org-rainbow-delimiters-depth-1">[</span> cos<span class="org-rainbow-delimiters-depth-2">(</span>Dh<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">5</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span> sin<span class="org-rainbow-delimiters-depth-2">(</span>Dh<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">5</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span>;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span>;
<span class="org-type">-</span>sin<span class="org-rainbow-delimiters-depth-2">(</span>Dh<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">5</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span> cos<span class="org-rainbow-delimiters-depth-2">(</span>Dh<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">5</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">]</span>;
Rhz = <span class="org-rainbow-delimiters-depth-1">[</span>cos<span class="org-rainbow-delimiters-depth-2">(</span>Dh<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">6</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-type">-</span>sin<span class="org-rainbow-delimiters-depth-2">(</span>Dh<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">6</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span>;
sin<span class="org-rainbow-delimiters-depth-2">(</span>Dh<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">6</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span> cos<span class="org-rainbow-delimiters-depth-2">(</span>Dh<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">6</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span>;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-1">]</span>;
Rh = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> Dh<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-2">)</span> ;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span> Dh<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-2">)</span> ;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> Dh<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-2">)</span> ;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-rainbow-delimiters-depth-1">]</span>;
Rh<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">1</span><span class="org-type">:</span><span class="org-highlight-numbers-number">3</span>, <span class="org-highlight-numbers-number">1</span><span class="org-type">:</span><span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-1">)</span> = Rhz<span class="org-type">*</span>Rhy<span class="org-type">*</span>Rhx;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Nano-Hexapod</span></span>
Rnx = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span>;
<span class="org-highlight-numbers-number">0</span> cos<span class="org-rainbow-delimiters-depth-2">(</span>Dn<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">4</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-type">-</span>sin<span class="org-rainbow-delimiters-depth-2">(</span>Dn<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">4</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span>;
<span class="org-highlight-numbers-number">0</span> sin<span class="org-rainbow-delimiters-depth-2">(</span>Dn<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">4</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span> cos<span class="org-rainbow-delimiters-depth-2">(</span>Dn<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">4</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">]</span>;
Rny = <span class="org-rainbow-delimiters-depth-1">[</span> cos<span class="org-rainbow-delimiters-depth-2">(</span>Dn<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">5</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span> sin<span class="org-rainbow-delimiters-depth-2">(</span>Dn<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">5</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span>;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span>;
<span class="org-type">-</span>sin<span class="org-rainbow-delimiters-depth-2">(</span>Dn<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">5</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span> cos<span class="org-rainbow-delimiters-depth-2">(</span>Dn<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">5</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">]</span>;
Rnz = <span class="org-rainbow-delimiters-depth-1">[</span>cos<span class="org-rainbow-delimiters-depth-2">(</span>Dn<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">6</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-type">-</span>sin<span class="org-rainbow-delimiters-depth-2">(</span>Dn<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">6</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span>;
sin<span class="org-rainbow-delimiters-depth-2">(</span>Dn<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">6</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span> cos<span class="org-rainbow-delimiters-depth-2">(</span>Dn<span class="org-rainbow-delimiters-depth-3">(</span><span class="org-highlight-numbers-number">6</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-highlight-numbers-number">0</span>;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-1">]</span>;
Rn = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> Dn<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-2">)</span> ;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span> Dn<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-2">)</span> ;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> Dn<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-2">)</span> ;
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">1</span> <span class="org-rainbow-delimiters-depth-1">]</span>;
Rn<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">1</span><span class="org-type">:</span><span class="org-highlight-numbers-number">3</span>, <span class="org-highlight-numbers-number">1</span><span class="org-type">:</span><span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-1">)</span> = Rnx<span class="org-type">*</span>Rny<span class="org-type">*</span>Rnz;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Total Homogeneous transformation</span></span>
WTr = Rty<span class="org-type">*</span>Rry<span class="org-type">*</span>Rrz<span class="org-type">*</span>Rh<span class="org-type">*</span>Rn;
<span class="org-keyword">end</span>
</pre>
</div>
</div>
</div>
</div>
</div>
<div id="postamble" class="status">
<p class="author">Author: Dehaeze Thomas</p>
<p class="date">Created: 2019-12-11 mer. 17:33</p>
<p class="validation"><a href="http://validator.w3.org/check?uri=referer">Validate</a></p>
</div>
</body>
</html>