1477 lines
198 KiB
HTML
1477 lines
198 KiB
HTML
<?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. 16:56 -->
|
|
<meta http-equiv="Content-Type" content="text/html;charset=utf-8" />
|
|
<meta name="viewport" content="width=device-width, initial-scale=1" />
|
|
<title>Subsystems used for the Simscape Models</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">Subsystems used for the Simscape Models</h1>
|
|
<div id="table-of-contents">
|
|
<h2>Table of Contents</h2>
|
|
<div id="text-table-of-contents">
|
|
<ul>
|
|
<li><a href="#org56f6ca1">1. Helping Functions</a>
|
|
<ul>
|
|
<li><a href="#orga234465">1.1. Generate Reference Signals</a></li>
|
|
<li><a href="#orgc45756f">1.2. Inverse Kinematics of the Hexapod</a></li>
|
|
</ul>
|
|
</li>
|
|
<li><a href="#org7f72373">2. Initialize Elements</a>
|
|
<ul>
|
|
<li><a href="#orgf7aa901">2.1. Ground</a></li>
|
|
<li><a href="#org0a81a44">2.2. Granite</a></li>
|
|
<li><a href="#orgdfdb545">2.3. Translation Stage</a></li>
|
|
<li><a href="#org915f4b0">2.4. Tilt Stage</a></li>
|
|
<li><a href="#orgf4527c4">2.5. Spindle</a></li>
|
|
<li><a href="#org4a4967e">2.6. Micro Hexapod</a></li>
|
|
<li><a href="#org263aa9c">2.7. Center of gravity compensation</a></li>
|
|
<li><a href="#org125d09f">2.8. Mirror</a></li>
|
|
<li><a href="#orgf1edf76">2.9. Nano Hexapod</a></li>
|
|
<li><a href="#orgde38f10">2.10. Cedrat Actuator</a></li>
|
|
<li><a href="#org3e33550">2.11. Sample</a></li>
|
|
</ul>
|
|
</li>
|
|
</ul>
|
|
</div>
|
|
</div>
|
|
|
|
<div id="outline-container-org56f6ca1" class="outline-2">
|
|
<h2 id="org56f6ca1"><span class="section-number-2">1</span> Helping Functions</h2>
|
|
<div class="outline-text-2" id="text-1">
|
|
</div>
|
|
<div id="outline-container-orga234465" class="outline-3">
|
|
<h3 id="orga234465"><span class="section-number-3">1.1</span> Generate Reference Signals</h3>
|
|
<div class="outline-text-3" id="text-1-1">
|
|
<p>
|
|
<a id="org89d4443"></a>
|
|
</p>
|
|
|
|
<p>
|
|
This Matlab function is accessible <a href="../src/initializeInputs.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">ref</span><span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">]</span></span> = <span class="org-function-name">initializeReferences</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-string">'Ts'</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-comment"> % Sampling Frequency [s]</span>
|
|
<span class="org-string">'Dy_type'</span>, <span class="org-string">'constant'</span>, ...<span class="org-comment"> % Either "constant" / "triangular" / "sinusoidal"</span>
|
|
<span class="org-string">'Dy_amplitude'</span>, <span class="org-highlight-numbers-number">0</span>, ...<span class="org-comment"> % Amplitude of the displacement [m]</span>
|
|
<span class="org-string">'Dy_period'</span>, <span class="org-highlight-numbers-number">1</span>, ...<span class="org-comment"> % Period of the displacement [s]</span>
|
|
<span class="org-string">'Ry_type'</span>, <span class="org-string">'constant'</span>, ...<span class="org-comment"> % Either "constant" / "triangular" / "sinusoidal"</span>
|
|
<span class="org-string">'Ry_amplitude'</span>, <span class="org-highlight-numbers-number">0</span>, ...<span class="org-comment"> % Amplitude [rad]</span>
|
|
<span class="org-string">'Ry_period'</span>, <span class="org-highlight-numbers-number">10</span>, ...<span class="org-comment"> % Period of the displacement [s]</span>
|
|
<span class="org-string">'Rz_type'</span>, <span class="org-string">'constant'</span>, ...<span class="org-comment"> % Either "constant" / "rotating"</span>
|
|
<span class="org-string">'Rz_amplitude'</span>, <span class="org-highlight-numbers-number">0</span>, ...<span class="org-comment"> % Initial angle [rad]</span>
|
|
<span class="org-string">'Rz_period'</span>, <span class="org-highlight-numbers-number">1</span>, ...<span class="org-comment"> % Period of the rotating [s]</span>
|
|
<span class="org-string">'Dh_type'</span>, <span class="org-string">'constant'</span>, ...<span class="org-comment"> % For now, only constant is implemented</span>
|
|
<span class="org-string">'Dh_pos'</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">0</span>; <span class="org-highlight-numbers-number">0</span>; <span class="org-highlight-numbers-number">0</span><span class="org-rainbow-delimiters-depth-2">]</span>, ...<span class="org-comment"> % Initial position [m,m,m,rad,rad,rad] of the top platform (Pitch-Roll-Yaw Euler angles)</span>
|
|
<span class="org-string">'Rm_type'</span>, <span class="org-string">'constant'</span>, ...<span class="org-comment"> % For now, only constant is implemented</span>
|
|
<span class="org-string">'Rm_pos'</span>, <span class="org-rainbow-delimiters-depth-2">[</span><span class="org-highlight-numbers-number">0</span>; <span class="org-constant">pi</span><span class="org-rainbow-delimiters-depth-2">]</span>, ...<span class="org-comment"> % Initial position of the two masses</span>
|
|
<span class="org-string">'Dn_type'</span>, <span class="org-string">'constant'</span>, ...<span class="org-comment"> % For now, only constant is implemented</span>
|
|
<span class="org-string">'Dn_pos'</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">0</span>; <span class="org-highlight-numbers-number">0</span>; <span class="org-highlight-numbers-number">0</span><span class="org-rainbow-delimiters-depth-2">]</span> ...<span class="org-comment"> % Initial position [m,m,m,rad,rad,rad] of the top platform</span>
|
|
<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">%% Set Sampling Time</span></span>
|
|
Ts = opts.Ts;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Translation stage - Dy</span></span>
|
|
t = <span class="org-highlight-numbers-number">0</span><span class="org-type">:</span>Ts<span class="org-type">:</span>opts.Dy_period<span class="org-type">-</span>Ts; <span class="org-comment">% Time Vector [s]</span>
|
|
Dy = zeros<span class="org-rainbow-delimiters-depth-1">(</span>length<span class="org-rainbow-delimiters-depth-2">(</span>t<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-keyword">switch</span> <span class="org-constant">opts.Dy_type</span>
|
|
<span class="org-keyword">case</span> <span class="org-string">'constant'</span>
|
|
Dy<span class="org-type"><span class="org-rainbow-delimiters-depth-1">(</span></span><span class="org-type">:</span><span class="org-type"><span class="org-rainbow-delimiters-depth-1">)</span></span><span class="org-type"> </span>= opts.Dy_amplitude;
|
|
<span class="org-keyword">case</span> <span class="org-string">'triangular'</span>
|
|
Dy<span class="org-type"><span class="org-rainbow-delimiters-depth-1">(</span></span><span class="org-type">:</span><span class="org-type"><span class="org-rainbow-delimiters-depth-1">)</span></span><span class="org-type"> </span>= <span class="org-type">-</span><span class="org-highlight-numbers-number">4</span><span class="org-type">*</span>opts.Dy_amplitude <span class="org-type">+</span> <span class="org-highlight-numbers-number">4</span><span class="org-type">*</span>opts.Dy_amplitude<span class="org-type">/</span>opts.Dy_period<span class="org-type">*</span>t;
|
|
Dy<span class="org-rainbow-delimiters-depth-1">(</span>t<span class="org-type"><</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">75</span><span class="org-type">*</span>opts.Dy_period<span class="org-rainbow-delimiters-depth-1">)</span> = <span class="org-highlight-numbers-number">2</span><span class="org-type">*</span>opts.Dy_amplitude <span class="org-type">-</span> <span class="org-highlight-numbers-number">4</span><span class="org-type">*</span>opts.Dy_amplitude<span class="org-type">/</span>opts.Dy_period<span class="org-type">*</span>t<span class="org-rainbow-delimiters-depth-1">(</span>t<span class="org-type"><</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">75</span><span class="org-type">*</span>opts.Dy_period<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
Dy<span class="org-rainbow-delimiters-depth-1">(</span>t<span class="org-type"><</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">25</span><span class="org-type">*</span>opts.Dy_period<span class="org-rainbow-delimiters-depth-1">)</span> = <span class="org-highlight-numbers-number">4</span><span class="org-type">*</span>opts.Dy_amplitude<span class="org-type">/</span>opts.Dy_period<span class="org-type">*</span>t<span class="org-rainbow-delimiters-depth-1">(</span>t<span class="org-type"><</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">25</span><span class="org-type">*</span>opts.Dy_period<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
<span class="org-keyword">case</span> <span class="org-string">'sinusoidal'</span>
|
|
Dy<span class="org-type"><span class="org-rainbow-delimiters-depth-1">(</span></span><span class="org-type">:</span><span class="org-type"><span class="org-rainbow-delimiters-depth-1">)</span></span><span class="org-type"> </span>= opts.Dy_amplitude<span class="org-type">*</span>sin<span class="org-rainbow-delimiters-depth-1">(</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>opts.Dy_period<span class="org-type">*</span>t<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
<span class="org-keyword">otherwise</span>
|
|
warning<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'Dy_type is not set correctly'</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
<span class="org-keyword">end</span>
|
|
Dy = struct<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'time'</span>, t, <span class="org-string">'signals'</span>, struct<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-string">'values'</span>, Dy<span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Tilt Stage - Ry</span></span>
|
|
t = <span class="org-highlight-numbers-number">0</span><span class="org-type">:</span>Ts<span class="org-type">:</span>opts.Ry_period<span class="org-type">-</span>Ts;
|
|
Ry = zeros<span class="org-rainbow-delimiters-depth-1">(</span>length<span class="org-rainbow-delimiters-depth-2">(</span>t<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-keyword">switch</span> <span class="org-constant">opts.Ry_type</span>
|
|
<span class="org-keyword">case</span> <span class="org-string">'constant'</span>
|
|
Ry<span class="org-type"><span class="org-rainbow-delimiters-depth-1">(</span></span><span class="org-type">:</span><span class="org-type"><span class="org-rainbow-delimiters-depth-1">)</span></span><span class="org-type"> </span>= opts.Ry_amplitude;
|
|
<span class="org-keyword">case</span> <span class="org-string">'triangular'</span>
|
|
Ry<span class="org-type"><span class="org-rainbow-delimiters-depth-1">(</span></span><span class="org-type">:</span><span class="org-type"><span class="org-rainbow-delimiters-depth-1">)</span></span><span class="org-type"> </span>= <span class="org-type">-</span><span class="org-highlight-numbers-number">4</span><span class="org-type">*</span>opts.Ry_amplitude <span class="org-type">+</span> <span class="org-highlight-numbers-number">4</span><span class="org-type">*</span>opts.Ry_amplitude<span class="org-type">/</span>opts.Ry_period<span class="org-type">*</span>t;
|
|
Ry<span class="org-rainbow-delimiters-depth-1">(</span>t<span class="org-type"><</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">75</span><span class="org-type">*</span>opts.Ry_period<span class="org-rainbow-delimiters-depth-1">)</span> = <span class="org-highlight-numbers-number">2</span><span class="org-type">*</span>opts.Ry_amplitude <span class="org-type">-</span> <span class="org-highlight-numbers-number">4</span><span class="org-type">*</span>opts.Ry_amplitude<span class="org-type">/</span>opts.Ry_period<span class="org-type">*</span>t<span class="org-rainbow-delimiters-depth-1">(</span>t<span class="org-type"><</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">75</span><span class="org-type">*</span>opts.Ry_period<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
Ry<span class="org-rainbow-delimiters-depth-1">(</span>t<span class="org-type"><</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">25</span><span class="org-type">*</span>opts.Ry_period<span class="org-rainbow-delimiters-depth-1">)</span> = <span class="org-highlight-numbers-number">4</span><span class="org-type">*</span>opts.Ry_amplitude<span class="org-type">/</span>opts.Ry_period<span class="org-type">*</span>t<span class="org-rainbow-delimiters-depth-1">(</span>t<span class="org-type"><</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">25</span><span class="org-type">*</span>opts.Ry_period<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
<span class="org-keyword">case</span> <span class="org-string">'sinusoidal'</span>
|
|
|
|
<span class="org-keyword">otherwise</span>
|
|
warning<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'Ry_type is not set correctly'</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
<span class="org-keyword">end</span>
|
|
Ry = struct<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'time'</span>, t, <span class="org-string">'signals'</span>, struct<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-string">'values'</span>, Ry<span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Spindle - Rz</span></span>
|
|
t = <span class="org-highlight-numbers-number">0</span><span class="org-type">:</span>Ts<span class="org-type">:</span>opts.Rz_period<span class="org-type">-</span>Ts;
|
|
Rz = zeros<span class="org-rainbow-delimiters-depth-1">(</span>length<span class="org-rainbow-delimiters-depth-2">(</span>t<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-keyword">switch</span> <span class="org-constant">opts.Rz_type</span>
|
|
<span class="org-keyword">case</span> <span class="org-string">'constant'</span>
|
|
Rz<span class="org-type"><span class="org-rainbow-delimiters-depth-1">(</span></span><span class="org-type">:</span><span class="org-type"><span class="org-rainbow-delimiters-depth-1">)</span></span><span class="org-type"> </span>= opts.Rz_amplitude;
|
|
<span class="org-keyword">case</span> <span class="org-string">'rotating'</span>
|
|
Rz<span class="org-type"><span class="org-rainbow-delimiters-depth-1">(</span></span><span class="org-type">:</span><span class="org-type"><span class="org-rainbow-delimiters-depth-1">)</span></span><span class="org-type"> </span>= opts.Rz_amplitude<span class="org-type">+</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>opts.Rz_period<span class="org-type">*</span>t;
|
|
<span class="org-keyword">otherwise</span>
|
|
warning<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'Rz_type is not set correctly'</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
<span class="org-keyword">end</span>
|
|
Rz = struct<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'time'</span>, t, <span class="org-string">'signals'</span>, struct<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-string">'values'</span>, Rz<span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Micro-Hexapod</span></span>
|
|
t = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>, Ts<span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
Dh = zeros<span class="org-rainbow-delimiters-depth-1">(</span>length<span class="org-rainbow-delimiters-depth-2">(</span>t<span class="org-rainbow-delimiters-depth-2">)</span>, <span class="org-highlight-numbers-number">6</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
Dhl = zeros<span class="org-rainbow-delimiters-depth-1">(</span>length<span class="org-rainbow-delimiters-depth-2">(</span>t<span class="org-rainbow-delimiters-depth-2">)</span>, <span class="org-highlight-numbers-number">6</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
<span class="org-keyword">switch</span> <span class="org-constant">opts.Dh_type</span>
|
|
<span class="org-keyword">case</span> <span class="org-string">'constant'</span>
|
|
Dh = <span class="org-rainbow-delimiters-depth-1">[</span>opts.Dh_pos, opts.Dh_pos<span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
|
|
load<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'./mat/stages.mat'</span>, <span class="org-string">'micro_hexapod'</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
AP = <span class="org-rainbow-delimiters-depth-1">[</span>opts.Dh_pos<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-2">)</span> ; opts.Dh_pos<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-2">)</span> ; opts.Dh_pos<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-rainbow-delimiters-depth-1">]</span>;
|
|
|
|
tx = opts.Dh_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>;
|
|
ty = opts.Dh_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>;
|
|
tz = opts.Dh_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>;
|
|
|
|
ARB = <span class="org-rainbow-delimiters-depth-1">[</span>cos<span class="org-rainbow-delimiters-depth-2">(</span>tz<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-type">-</span>sin<span class="org-rainbow-delimiters-depth-2">(</span>tz<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>tz<span class="org-rainbow-delimiters-depth-2">)</span> cos<span class="org-rainbow-delimiters-depth-2">(</span>tz<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-type">*</span>...
|
|
<span class="org-rainbow-delimiters-depth-1">[</span> cos<span class="org-rainbow-delimiters-depth-2">(</span>ty<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>ty<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>ty<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>ty<span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">]</span><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> cos<span class="org-rainbow-delimiters-depth-2">(</span>tx<span class="org-rainbow-delimiters-depth-2">)</span> <span class="org-type">-</span>sin<span class="org-rainbow-delimiters-depth-2">(</span>tx<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>tx<span class="org-rainbow-delimiters-depth-2">)</span> cos<span class="org-rainbow-delimiters-depth-2">(</span>tx<span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
|
|
<span class="org-rainbow-delimiters-depth-1">[</span>Dhl<span class="org-rainbow-delimiters-depth-1">]</span> = inverseKinematicsHexapod<span class="org-rainbow-delimiters-depth-1">(</span>micro_hexapod, AP, ARB<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
Dhl = <span class="org-rainbow-delimiters-depth-1">[</span>Dhl, Dhl<span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
<span class="org-keyword">otherwise</span>
|
|
warning<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'Dh_type is not set correctly'</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
<span class="org-keyword">end</span>
|
|
Dh = struct<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'time'</span>, t, <span class="org-string">'signals'</span>, struct<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-string">'values'</span>, Dh<span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
Dhl = struct<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'time'</span>, t, <span class="org-string">'signals'</span>, struct<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-string">'values'</span>, Dhl<span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Axis Compensation - Rm</span></span>
|
|
t = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>, Ts<span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
Rm = <span class="org-rainbow-delimiters-depth-1">[</span>opts.Rm_pos, opts.Rm_pos<span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
Rm = struct<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'time'</span>, t, <span class="org-string">'signals'</span>, struct<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-string">'values'</span>, Rm<span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Nano-Hexapod</span></span>
|
|
t = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>, Ts<span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
Dn = zeros<span class="org-rainbow-delimiters-depth-1">(</span>length<span class="org-rainbow-delimiters-depth-2">(</span>t<span class="org-rainbow-delimiters-depth-2">)</span>, <span class="org-highlight-numbers-number">6</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
<span class="org-keyword">switch</span> <span class="org-constant">opts.Dn_type</span>
|
|
<span class="org-keyword">case</span> <span class="org-string">'constant'</span>
|
|
Dn = <span class="org-rainbow-delimiters-depth-1">[</span>opts.Dn_pos, opts.Dn_pos<span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
<span class="org-keyword">otherwise</span>
|
|
warning<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'Dn_type is not set correctly'</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
<span class="org-keyword">end</span>
|
|
Dn = struct<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'time'</span>, t, <span class="org-string">'signals'</span>, struct<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-string">'values'</span>, Dn<span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Save</span></span>
|
|
save<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'./mat/nass_references.mat'</span>, <span class="org-string">'Dy'</span>, <span class="org-string">'Ry'</span>, <span class="org-string">'Rz'</span>, <span class="org-string">'Dh'</span>, <span class="org-string">'Dhl'</span>, <span class="org-string">'Rm'</span>, <span class="org-string">'Dn'</span>, <span class="org-string">'Ts'</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
<span class="org-keyword">end</span>
|
|
</pre>
|
|
</div>
|
|
</div>
|
|
</div>
|
|
|
|
<div id="outline-container-orgc45756f" class="outline-3">
|
|
<h3 id="orgc45756f"><span class="section-number-3">1.2</span> Inverse Kinematics of the Hexapod</h3>
|
|
<div class="outline-text-3" id="text-1-2">
|
|
<p>
|
|
<a id="org83a2692"></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>
|
|
|
|
|
|
<div id="outline-container-org7f72373" class="outline-2">
|
|
<h2 id="org7f72373"><span class="section-number-2">2</span> Initialize Elements</h2>
|
|
<div class="outline-text-2" id="text-2">
|
|
<p>
|
|
<a id="org8d34300"></a>
|
|
</p>
|
|
</div>
|
|
<div id="outline-container-orgf7aa901" class="outline-3">
|
|
<h3 id="orgf7aa901"><span class="section-number-3">2.1</span> Ground</h3>
|
|
<div class="outline-text-3" id="text-2-1">
|
|
<p>
|
|
<a id="org1b8ee2f"></a>
|
|
</p>
|
|
|
|
<p>
|
|
This Matlab function is accessible <a href="../src/initializeGround.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">ground</span><span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">]</span></span> = <span class="org-function-name">initializeGround</span><span class="org-rainbow-delimiters-depth-1">()</span>
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%%</span></span>
|
|
ground = struct<span class="org-rainbow-delimiters-depth-1">()</span>;
|
|
|
|
ground.shape = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">2</span>, <span class="org-highlight-numbers-number">2</span>, <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">5</span><span class="org-rainbow-delimiters-depth-1">]</span>; <span class="org-comment">% [m]</span>
|
|
ground.density = <span class="org-highlight-numbers-number">2800</span>; <span class="org-comment">% [kg/m3]</span>
|
|
ground.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">5</span>, <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">5</span>, <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">5</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Save</span></span>
|
|
save<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'./mat/stages.mat'</span>, <span class="org-string">'ground'</span>, <span class="org-string">'-append'</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
<span class="org-keyword">end</span>
|
|
</pre>
|
|
</div>
|
|
</div>
|
|
</div>
|
|
|
|
<div id="outline-container-org0a81a44" class="outline-3">
|
|
<h3 id="org0a81a44"><span class="section-number-3">2.2</span> Granite</h3>
|
|
<div class="outline-text-3" id="text-2-2">
|
|
<p>
|
|
<a id="orge161933"></a>
|
|
</p>
|
|
|
|
<p>
|
|
This Matlab function is accessible <a href="../src/initializeGranite.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">granite</span><span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">]</span></span> = <span class="org-function-name">initializeGranite</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-string">'rigid'</span>, <span class="org-constant">false</span><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">%%</span></span>
|
|
granite = struct<span class="org-rainbow-delimiters-depth-1">()</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Static Properties</span></span>
|
|
granite.density = <span class="org-highlight-numbers-number">2800</span>; <span class="org-comment">% [kg/m3]</span>
|
|
granite.volume = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">749</span>; <span class="org-comment">% [m3] TODO - should</span>
|
|
granite.mass = granite.density<span class="org-type">*</span>granite.volume; <span class="org-comment">% [kg]</span>
|
|
granite.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">1</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
granite.STEP = <span class="org-string">'./STEPS/granite/granite.STEP'</span>;
|
|
|
|
granite.mass_top = <span class="org-highlight-numbers-number">4000</span>; <span class="org-comment">% [kg] TODO</span>
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Dynamical Properties</span></span>
|
|
<span class="org-keyword">if</span> opts.rigid
|
|
granite.k.x = <span class="org-highlight-numbers-number">1e12</span>; <span class="org-comment">% [N/m]</span>
|
|
granite.k.y = <span class="org-highlight-numbers-number">1e12</span>; <span class="org-comment">% [N/m]</span>
|
|
granite.k.z = <span class="org-highlight-numbers-number">1e12</span>; <span class="org-comment">% [N/m]</span>
|
|
granite.k.rx = <span class="org-highlight-numbers-number">1e10</span>; <span class="org-comment">% [N*m/deg]</span>
|
|
granite.k.ry = <span class="org-highlight-numbers-number">1e10</span>; <span class="org-comment">% [N*m/deg]</span>
|
|
granite.k.rz = <span class="org-highlight-numbers-number">1e10</span>; <span class="org-comment">% [N*m/deg]</span>
|
|
<span class="org-keyword">else</span>
|
|
granite.k.x = <span class="org-highlight-numbers-number">4e9</span>; <span class="org-comment">% [N/m]</span>
|
|
granite.k.y = <span class="org-highlight-numbers-number">3e8</span>; <span class="org-comment">% [N/m]</span>
|
|
granite.k.z = <span class="org-highlight-numbers-number">8e8</span>; <span class="org-comment">% [N/m]</span>
|
|
granite.k.rx = <span class="org-highlight-numbers-number">1e4</span>; <span class="org-comment">% [N*m/deg]</span>
|
|
granite.k.ry = <span class="org-highlight-numbers-number">1e4</span>; <span class="org-comment">% [N*m/deg]</span>
|
|
granite.k.rz = <span class="org-highlight-numbers-number">1e6</span>; <span class="org-comment">% [N*m/deg]</span>
|
|
<span class="org-keyword">end</span>
|
|
|
|
granite.c.x = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">1</span><span class="org-type">*</span>sqrt<span class="org-rainbow-delimiters-depth-1">(</span>granite.mass_top<span class="org-type">*</span>granite.k.x<span class="org-rainbow-delimiters-depth-1">)</span>; <span class="org-comment">% [N/(m/s)]</span>
|
|
granite.c.y = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">1</span><span class="org-type">*</span>sqrt<span class="org-rainbow-delimiters-depth-1">(</span>granite.mass_top<span class="org-type">*</span>granite.k.y<span class="org-rainbow-delimiters-depth-1">)</span>; <span class="org-comment">% [N/(m/s)]</span>
|
|
granite.c.z = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">5</span><span class="org-type">*</span>sqrt<span class="org-rainbow-delimiters-depth-1">(</span>granite.mass_top<span class="org-type">*</span>granite.k.z<span class="org-rainbow-delimiters-depth-1">)</span>; <span class="org-comment">% [N/(m/s)]</span>
|
|
granite.c.rx = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">1</span><span class="org-type">*</span>sqrt<span class="org-rainbow-delimiters-depth-1">(</span>granite.mass_top<span class="org-type">*</span>granite.k.rx<span class="org-rainbow-delimiters-depth-1">)</span>; <span class="org-comment">% [N*m/(deg/s)]</span>
|
|
granite.c.ry = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">1</span><span class="org-type">*</span>sqrt<span class="org-rainbow-delimiters-depth-1">(</span>granite.mass_top<span class="org-type">*</span>granite.k.ry<span class="org-rainbow-delimiters-depth-1">)</span>; <span class="org-comment">% [N*m/(deg/s)]</span>
|
|
granite.c.rz = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">1</span><span class="org-type">*</span>sqrt<span class="org-rainbow-delimiters-depth-1">(</span>granite.mass_top<span class="org-type">*</span>granite.k.rz<span class="org-rainbow-delimiters-depth-1">)</span>; <span class="org-comment">% [N*m/(deg/s)]</span>
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Positioning parameters</span></span>
|
|
granite.sample_pos = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">8</span>; <span class="org-comment">% Z-offset for the initial position of the sample [m]</span>
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Save</span></span>
|
|
save<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'./mat/stages.mat'</span>, <span class="org-string">'granite'</span>, <span class="org-string">'-append'</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
<span class="org-keyword">end</span>
|
|
</pre>
|
|
</div>
|
|
</div>
|
|
</div>
|
|
|
|
<div id="outline-container-orgdfdb545" class="outline-3">
|
|
<h3 id="orgdfdb545"><span class="section-number-3">2.3</span> Translation Stage</h3>
|
|
<div class="outline-text-3" id="text-2-3">
|
|
<p>
|
|
<a id="org062a294"></a>
|
|
</p>
|
|
|
|
<p>
|
|
This Matlab function is accessible <a href="../src/initializeTy.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">ty</span><span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">]</span></span> = <span class="org-function-name">initializeTy</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-string">'rigid'</span>, <span class="org-constant">false</span><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">%%</span></span>
|
|
ty = struct<span class="org-rainbow-delimiters-depth-1">()</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Y-Translation - Static Properties</span></span>
|
|
<span class="org-comment">% Ty Granite frame</span>
|
|
ty.granite_frame.density = <span class="org-highlight-numbers-number">7800</span>; <span class="org-comment">% [kg/m3]</span>
|
|
ty.granite_frame.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">753</span> <span class="org-highlight-numbers-number">1</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">753</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
ty.granite_frame.STEP = <span class="org-string">'./STEPS/Ty/Ty_Granite_Frame.STEP'</span>;
|
|
<span class="org-comment">% Guide Translation Ty</span>
|
|
ty.guide.density = <span class="org-highlight-numbers-number">7800</span>; <span class="org-comment">% [kg/m3]</span>
|
|
ty.guide.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">792</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">820</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">933</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
ty.guide.STEP = <span class="org-string">'./STEPS/ty/Ty_Guide.STEP'</span>;
|
|
<span class="org-comment">% Ty - Guide_Translation12</span>
|
|
ty.guide12.density = <span class="org-highlight-numbers-number">7800</span>; <span class="org-comment">% [kg/m3]</span>
|
|
ty.guide12.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">792</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">820</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">933</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
ty.guide12.STEP = <span class="org-string">'./STEPS/Ty/Ty_Guide_12.STEP'</span>;
|
|
<span class="org-comment">% Ty - Guide_Translation11</span>
|
|
ty.guide11.density = <span class="org-highlight-numbers-number">7800</span>; <span class="org-comment">% [kg/m3]</span>
|
|
ty.guide11.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">792</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">820</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">933</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
ty.guide11.STEP = <span class="org-string">'./STEPS/ty/Ty_Guide_11.STEP'</span>;
|
|
<span class="org-comment">% Ty - Guide_Translation22</span>
|
|
ty.guide22.density = <span class="org-highlight-numbers-number">7800</span>; <span class="org-comment">% [kg/m3]</span>
|
|
ty.guide22.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">792</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">820</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">933</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
ty.guide22.STEP = <span class="org-string">'./STEPS/ty/Ty_Guide_22.STEP'</span>;
|
|
<span class="org-comment">% Ty - Guide_Translation21</span>
|
|
ty.guide21.density = <span class="org-highlight-numbers-number">7800</span>; <span class="org-comment">% [kg/m3]</span>
|
|
ty.guide21.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">792</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">820</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">933</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
ty.guide21.STEP = <span class="org-string">'./STEPS/Ty/Ty_Guide_21.STEP'</span>;
|
|
<span class="org-comment">% Ty - Plateau translation</span>
|
|
ty.frame.density = <span class="org-highlight-numbers-number">7800</span>; <span class="org-comment">% [kg/m3]</span>
|
|
ty.frame.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">792</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">820</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">933</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
ty.frame.STEP = <span class="org-string">'./STEPS/ty/Ty_Stage.STEP'</span>;
|
|
<span class="org-comment">% Ty Stator Part</span>
|
|
ty.stator.density = <span class="org-highlight-numbers-number">5400</span>; <span class="org-comment">% [kg/m3]</span>
|
|
ty.stator.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">792</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">820</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">933</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
ty.stator.STEP = <span class="org-string">'./STEPS/ty/Ty_Motor_Stator.STEP'</span>;
|
|
<span class="org-comment">% Ty Rotor Part</span>
|
|
ty.rotor.density = <span class="org-highlight-numbers-number">5400</span>; <span class="org-comment">% [kg/m3]</span>
|
|
ty.rotor.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">792</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">820</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">933</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
ty.rotor.STEP = <span class="org-string">'./STEPS/ty/Ty_Motor_Rotor.STEP'</span>;
|
|
|
|
ty.m = <span class="org-highlight-numbers-number">1000</span>; <span class="org-comment">% TODO [kg]</span>
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Y-Translation - Dynamicals Properties</span></span>
|
|
<span class="org-keyword">if</span> opts.rigid
|
|
ty.k.ax = <span class="org-highlight-numbers-number">1e12</span>; % Axial Stiffness <span class="org-keyword">for</span> each of the <span class="org-highlight-numbers-number">4</span> guidance (y) [N<span class="org-type">/</span>m]
|
|
ty.k.rad = <span class="org-highlight-numbers-number">1e12</span>; % Radial Stiffness <span class="org-keyword">for</span> each of the <span class="org-highlight-numbers-number">4</span> guidance (x<span class="org-type">-</span>z) [N<span class="org-type">/</span>m]
|
|
<span class="org-keyword">else</span>
|
|
ty.k.ax = <span class="org-highlight-numbers-number">5e8</span>; % Axial Stiffness <span class="org-keyword">for</span> each of the <span class="org-highlight-numbers-number">4</span> guidance (y) [N<span class="org-type">/</span>m]
|
|
ty.k.rad = <span class="org-highlight-numbers-number">5e7</span>; % Radial Stiffness <span class="org-keyword">for</span> each of the <span class="org-highlight-numbers-number">4</span> guidance (x<span class="org-type">-</span>z) [N<span class="org-type">/</span>m]
|
|
<span class="org-keyword">end</span>
|
|
|
|
ty.c.ax = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">1</span><span class="org-type">*</span>sqrt<span class="org-rainbow-delimiters-depth-1">(</span>ty.k.ax<span class="org-type">*</span>ty.m<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
ty.c.rad = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">1</span><span class="org-type">*</span>sqrt<span class="org-rainbow-delimiters-depth-1">(</span>ty.k.rad<span class="org-type">*</span>ty.m<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Save</span></span>
|
|
save<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'./mat/stages.mat'</span>, <span class="org-string">'ty'</span>, <span class="org-string">'-append'</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
<span class="org-keyword">end</span>
|
|
</pre>
|
|
</div>
|
|
</div>
|
|
</div>
|
|
|
|
<div id="outline-container-org915f4b0" class="outline-3">
|
|
<h3 id="org915f4b0"><span class="section-number-3">2.4</span> Tilt Stage</h3>
|
|
<div class="outline-text-3" id="text-2-4">
|
|
<p>
|
|
<a id="orgc307396"></a>
|
|
</p>
|
|
|
|
<p>
|
|
This Matlab function is accessible <a href="../src/initializeRy.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">ry</span><span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">]</span></span> = <span class="org-function-name">initializeRy</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-string">'rigid'</span>, <span class="org-constant">false</span><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">%%</span></span>
|
|
ry = struct<span class="org-rainbow-delimiters-depth-1">()</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Tilt Stage - Static Properties</span></span>
|
|
<span class="org-comment">% Ry - Guide for the tilt stage</span>
|
|
ry.guide.density = <span class="org-highlight-numbers-number">7800</span>; <span class="org-comment">% [kg/m3]</span>
|
|
ry.guide.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">792</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">820</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">933</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
ry.guide.STEP = <span class="org-string">'./STEPS/ry/Tilt_Guide.STEP'</span>;
|
|
<span class="org-comment">% Ry - Rotor of the motor</span>
|
|
ry.rotor.density = <span class="org-highlight-numbers-number">2400</span>; <span class="org-comment">% [kg/m3]</span>
|
|
ry.rotor.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">792</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">820</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">933</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
ry.rotor.STEP = <span class="org-string">'./STEPS/ry/Tilt_Motor_Axis.STEP'</span>;
|
|
<span class="org-comment">% Ry - Motor</span>
|
|
ry.motor.density = <span class="org-highlight-numbers-number">3200</span>; <span class="org-comment">% [kg/m3]</span>
|
|
ry.motor.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">792</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">820</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">933</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
ry.motor.STEP = <span class="org-string">'./STEPS/ry/Tilt_Motor.STEP'</span>;
|
|
<span class="org-comment">% Ry - Plateau Tilt</span>
|
|
ry.stage.density = <span class="org-highlight-numbers-number">7800</span>; <span class="org-comment">% [kg/m3]</span>
|
|
ry.stage.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">792</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">820</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">933</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
ry.stage.STEP = <span class="org-string">'./STEPS/ry/Tilt_Stage.STEP'</span>;
|
|
|
|
ry.m = <span class="org-highlight-numbers-number">800</span>; <span class="org-comment">% TODO [kg]</span>
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Tilt Stage - Dynamical Properties</span></span>
|
|
<span class="org-keyword">if</span> opts.rigid
|
|
ry.k.tilt = <span class="org-highlight-numbers-number">1e10</span>; <span class="org-comment">% Rotation stiffness around y [N*m/deg]</span>
|
|
ry.k.h = <span class="org-highlight-numbers-number">1e12</span>; <span class="org-comment">% Stiffness in the direction of the guidance [N/m]</span>
|
|
ry.k.rad = <span class="org-highlight-numbers-number">1e12</span>; <span class="org-comment">% Stiffness in the top direction [N/m]</span>
|
|
ry.k.rrad = <span class="org-highlight-numbers-number">1e12</span>; <span class="org-comment">% Stiffness in the side direction [N/m]</span>
|
|
<span class="org-keyword">else</span>
|
|
ry.k.tilt = <span class="org-highlight-numbers-number">1e4</span>; <span class="org-comment">% Rotation stiffness around y [N*m/deg]</span>
|
|
ry.k.h = <span class="org-highlight-numbers-number">1e8</span>; <span class="org-comment">% Stiffness in the direction of the guidance [N/m]</span>
|
|
ry.k.rad = <span class="org-highlight-numbers-number">1e8</span>; <span class="org-comment">% Stiffness in the top direction [N/m]</span>
|
|
ry.k.rrad = <span class="org-highlight-numbers-number">1e8</span>; <span class="org-comment">% Stiffness in the side direction [N/m]</span>
|
|
<span class="org-keyword">end</span>
|
|
|
|
ry.c.h = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">1</span><span class="org-type">*</span>sqrt<span class="org-rainbow-delimiters-depth-1">(</span>ry.k.h<span class="org-type">*</span>ry.m<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
ry.c.rad = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">1</span><span class="org-type">*</span>sqrt<span class="org-rainbow-delimiters-depth-1">(</span>ry.k.rad<span class="org-type">*</span>ry.m<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
ry.c.rrad = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">1</span><span class="org-type">*</span>sqrt<span class="org-rainbow-delimiters-depth-1">(</span>ry.k.rrad<span class="org-type">*</span>ry.m<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
ry.c.tilt = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">1</span><span class="org-type">*</span>sqrt<span class="org-rainbow-delimiters-depth-1">(</span>ry.k.tilt<span class="org-type">*</span>ry.m<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Positioning parameters</span></span>
|
|
ry.z_offset = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">58178</span>; <span class="org-comment">% Z-Offset so that the center of rotation matches the sample center [m]</span>
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Save</span></span>
|
|
save<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'./mat/stages.mat'</span>, <span class="org-string">'ry'</span>, <span class="org-string">'-append'</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
<span class="org-keyword">end</span>
|
|
</pre>
|
|
</div>
|
|
</div>
|
|
</div>
|
|
|
|
<div id="outline-container-orgf4527c4" class="outline-3">
|
|
<h3 id="orgf4527c4"><span class="section-number-3">2.5</span> Spindle</h3>
|
|
<div class="outline-text-3" id="text-2-5">
|
|
<p>
|
|
<a id="orgc775c74"></a>
|
|
</p>
|
|
|
|
<p>
|
|
This Matlab function is accessible <a href="../src/initializeRz.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">rz</span><span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">]</span></span> = <span class="org-function-name">initializeRz</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-string">'rigid'</span>, <span class="org-constant">false</span><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">%%</span></span>
|
|
rz = struct<span class="org-rainbow-delimiters-depth-1">()</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Spindle - Static Properties</span></span>
|
|
<span class="org-comment">% Spindle - Slip Ring</span>
|
|
rz.slipring.density = <span class="org-highlight-numbers-number">7800</span>; <span class="org-comment">% [kg/m3]</span>
|
|
rz.slipring.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">792</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">820</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">933</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
rz.slipring.STEP = <span class="org-string">'./STEPS/rz/Spindle_Slip_Ring.STEP'</span>;
|
|
<span class="org-comment">% Spindle - Rotor</span>
|
|
rz.rotor.density = <span class="org-highlight-numbers-number">7800</span>; <span class="org-comment">% [kg/m3]</span>
|
|
rz.rotor.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">792</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">820</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">933</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
rz.rotor.STEP = <span class="org-string">'./STEPS/rz/Spindle_Rotor.STEP'</span>;
|
|
<span class="org-comment">% Spindle - Stator</span>
|
|
rz.stator.density = <span class="org-highlight-numbers-number">7800</span>; <span class="org-comment">% [kg/m3]</span>
|
|
rz.stator.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">792</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">820</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">933</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
rz.stator.STEP = <span class="org-string">'./STEPS/rz/Spindle_Stator.STEP'</span>;
|
|
|
|
<span class="org-comment">% Estimated mass of the mooving part</span>
|
|
rz.m = <span class="org-highlight-numbers-number">250</span>; <span class="org-comment">% [kg]</span>
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Spindle - Dynamical Properties</span></span>
|
|
|
|
<span class="org-keyword">if</span> opts.rigid
|
|
rz.k.rot = <span class="org-highlight-numbers-number">1e10</span>; <span class="org-comment">% Rotational Stiffness (Rz) [N*m/deg]</span>
|
|
rz.k.tilt = <span class="org-highlight-numbers-number">1e10</span>; <span class="org-comment">% Rotational Stiffness (Rx, Ry) [N*m/deg]</span>
|
|
rz.k.ax = <span class="org-highlight-numbers-number">1e12</span>; <span class="org-comment">% Axial Stiffness (Z) [N/m]</span>
|
|
rz.k.rad = <span class="org-highlight-numbers-number">1e12</span>; <span class="org-comment">% Radial Stiffness (X, Y) [N/m]</span>
|
|
<span class="org-keyword">else</span>
|
|
rz.k.rot = <span class="org-highlight-numbers-number">1e6</span>; <span class="org-comment">% TODO - Rotational Stiffness (Rz) [N*m/deg]</span>
|
|
rz.k.tilt = <span class="org-highlight-numbers-number">1e6</span>; <span class="org-comment">% Rotational Stiffness (Rx, Ry) [N*m/deg]</span>
|
|
rz.k.ax = <span class="org-highlight-numbers-number">2e9</span>; <span class="org-comment">% Axial Stiffness (Z) [N/m]</span>
|
|
rz.k.rad = <span class="org-highlight-numbers-number">7e8</span>; <span class="org-comment">% Radial Stiffness (X, Y) [N/m]</span>
|
|
<span class="org-keyword">end</span>
|
|
|
|
<span class="org-comment">% Damping</span>
|
|
rz.c.ax = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">1</span><span class="org-type">*</span>sqrt<span class="org-rainbow-delimiters-depth-1">(</span>rz.k.ax<span class="org-type">*</span>rz.m<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
rz.c.rad = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">1</span><span class="org-type">*</span>sqrt<span class="org-rainbow-delimiters-depth-1">(</span>rz.k.rad<span class="org-type">*</span>rz.m<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
rz.c.tilt = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">1</span><span class="org-type">*</span>sqrt<span class="org-rainbow-delimiters-depth-1">(</span>rz.k.tilt<span class="org-type">*</span>rz.m<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
rz.c.rot = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">1</span><span class="org-type">*</span>sqrt<span class="org-rainbow-delimiters-depth-1">(</span>rz.k.rot<span class="org-type">*</span>rz.m<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Save</span></span>
|
|
save<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'./mat/stages.mat'</span>, <span class="org-string">'rz'</span>, <span class="org-string">'-append'</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
<span class="org-keyword">end</span>
|
|
</pre>
|
|
</div>
|
|
</div>
|
|
</div>
|
|
|
|
<div id="outline-container-org4a4967e" class="outline-3">
|
|
<h3 id="org4a4967e"><span class="section-number-3">2.6</span> Micro Hexapod</h3>
|
|
<div class="outline-text-3" id="text-2-6">
|
|
<p>
|
|
<a id="orge156c79"></a>
|
|
</p>
|
|
|
|
<p>
|
|
This Matlab function is accessible <a href="../src/initializeMicroHexapod.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">micro_hexapod</span><span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">]</span></span> = <span class="org-function-name">initializeMicroHexapod</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-string">'rigid'</span>, <span class="org-constant">false</span>, ...
|
|
<span class="org-string">'AP'</span>, zeros<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-comment"> % Wanted position in [m] of OB with respect to frame {A}</span>
|
|
<span class="org-string">'ARB'</span>, eye<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-comment"> % Rotation Matrix that represent the wanted orientation of frame {B} with respect to frame {A}</span>
|
|
<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">%% Stewart Object</span></span>
|
|
micro_hexapod = struct<span class="org-rainbow-delimiters-depth-1">()</span>;
|
|
micro_hexapod.h = <span class="org-highlight-numbers-number">350</span>; <span class="org-comment">% Total height of the platform [mm]</span>
|
|
micro_hexapod.jacobian = <span class="org-highlight-numbers-number">270</span>; <span class="org-comment">% Distance from the top of the mobile platform to the Jacobian point [mm]</span>
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Bottom Plate - Mechanical Design</span></span>
|
|
BP = struct<span class="org-rainbow-delimiters-depth-1">()</span>;
|
|
|
|
BP.rad.int = <span class="org-highlight-numbers-number">110</span>; <span class="org-comment">% Internal Radius [mm]</span>
|
|
BP.rad.ext = <span class="org-highlight-numbers-number">207</span>.<span class="org-highlight-numbers-number">5</span>; <span class="org-comment">% External Radius [mm]</span>
|
|
BP.thickness = <span class="org-highlight-numbers-number">26</span>; <span class="org-comment">% Thickness [mm]</span>
|
|
BP.leg.rad = <span class="org-highlight-numbers-number">175</span>.<span class="org-highlight-numbers-number">5</span>; <span class="org-comment">% Radius where the legs articulations are positionned [mm]</span>
|
|
BP.leg.ang = <span class="org-highlight-numbers-number">9</span>.<span class="org-highlight-numbers-number">5</span>; <span class="org-comment">% Angle Offset [deg]</span>
|
|
BP.density = <span class="org-highlight-numbers-number">8000</span>; % Density of the material [kg<span class="org-type">/</span>m<span class="org-type">^</span><span class="org-highlight-numbers-number">3</span>]
|
|
BP.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">6</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">6</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">6</span><span class="org-rainbow-delimiters-depth-1">]</span>; <span class="org-comment">% Color [rgb]</span>
|
|
BP.shape = <span class="org-rainbow-delimiters-depth-1">[</span>BP.rad.int BP.thickness; BP.rad.int <span class="org-highlight-numbers-number">0</span>; BP.rad.ext <span class="org-highlight-numbers-number">0</span>; BP.rad.ext BP.thickness<span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Top Plate - Mechanical Design</span></span>
|
|
TP = struct<span class="org-rainbow-delimiters-depth-1">()</span>;
|
|
|
|
TP.rad.int = <span class="org-highlight-numbers-number">82</span>; <span class="org-comment">% Internal Radius [mm]</span>
|
|
TP.rad.ext = <span class="org-highlight-numbers-number">150</span>; <span class="org-comment">% Internal Radius [mm]</span>
|
|
TP.thickness = <span class="org-highlight-numbers-number">26</span>; <span class="org-comment">% Thickness [mm]</span>
|
|
TP.leg.rad = <span class="org-highlight-numbers-number">118</span>; <span class="org-comment">% Radius where the legs articulations are positionned [mm]</span>
|
|
TP.leg.ang = <span class="org-highlight-numbers-number">12</span>.<span class="org-highlight-numbers-number">1</span>; <span class="org-comment">% Angle Offset [deg]</span>
|
|
TP.density = <span class="org-highlight-numbers-number">8000</span>; % Density of the material [kg<span class="org-type">/</span>m<span class="org-type">^</span><span class="org-highlight-numbers-number">3</span>]
|
|
TP.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">6</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">6</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">6</span><span class="org-rainbow-delimiters-depth-1">]</span>; <span class="org-comment">% Color [rgb]</span>
|
|
TP.shape = <span class="org-rainbow-delimiters-depth-1">[</span>TP.rad.int TP.thickness; TP.rad.int <span class="org-highlight-numbers-number">0</span>; TP.rad.ext <span class="org-highlight-numbers-number">0</span>; TP.rad.ext TP.thickness<span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Struts</span></span>
|
|
Leg = struct<span class="org-rainbow-delimiters-depth-1">()</span>;
|
|
|
|
Leg.stroke = <span class="org-highlight-numbers-number">10e</span><span class="org-type">-</span><span class="org-highlight-numbers-number">3</span>; <span class="org-comment">% Maximum Stroke of each leg [m]</span>
|
|
<span class="org-keyword">if</span> opts.rigid
|
|
Leg.k.ax = <span class="org-highlight-numbers-number">1e12</span>; <span class="org-comment">% Stiffness of each leg [N/m]</span>
|
|
<span class="org-keyword">else</span>
|
|
Leg.k.ax = <span class="org-highlight-numbers-number">2e7</span>; <span class="org-comment">% Stiffness of each leg [N/m]</span>
|
|
<span class="org-keyword">end</span>
|
|
Leg.ksi.ax = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">1</span>; % Modal damping ksi = <span class="org-highlight-numbers-number">1</span><span class="org-type">/</span><span class="org-highlight-numbers-number">2</span><span class="org-type">*</span>c<span class="org-type">/</span>sqrt(km) []
|
|
Leg.rad.bottom = <span class="org-highlight-numbers-number">25</span>; <span class="org-comment">% Radius of the cylinder of the bottom part [mm]</span>
|
|
Leg.rad.top = <span class="org-highlight-numbers-number">17</span>; <span class="org-comment">% Radius of the cylinder of the top part [mm]</span>
|
|
Leg.density = <span class="org-highlight-numbers-number">8000</span>; % Density of the material [kg<span class="org-type">/</span>m<span class="org-type">^</span><span class="org-highlight-numbers-number">3</span>]
|
|
Leg.color.bottom = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">5</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">5</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">5</span><span class="org-rainbow-delimiters-depth-1">]</span>; <span class="org-comment">% Color [rgb]</span>
|
|
Leg.color.top = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">5</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">5</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">5</span><span class="org-rainbow-delimiters-depth-1">]</span>; <span class="org-comment">% Color [rgb]</span>
|
|
|
|
Leg.sphere.bottom = Leg.rad.bottom; <span class="org-comment">% Size of the sphere at the end of the leg [mm]</span>
|
|
Leg.sphere.top = Leg.rad.top; <span class="org-comment">% Size of the sphere at the end of the leg [mm]</span>
|
|
Leg.m = TP.density<span class="org-type">*</span><span class="org-rainbow-delimiters-depth-1">(</span><span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">pi</span><span class="org-type">*</span><span class="org-rainbow-delimiters-depth-3">(</span>TP.rad.ext<span class="org-type">/</span><span class="org-highlight-numbers-number">1000</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-type">^</span><span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">*</span><span class="org-rainbow-delimiters-depth-2">(</span>TP.thickness<span class="org-type">/</span><span class="org-highlight-numbers-number">1000</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">-</span><span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">pi</span><span class="org-type">*</span><span class="org-rainbow-delimiters-depth-3">(</span>TP.rad.int<span class="org-type">/</span><span class="org-highlight-numbers-number">1000</span><span class="org-type">^</span><span class="org-highlight-numbers-number">2</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-rainbow-delimiters-depth-2">(</span>TP.thickness<span class="org-type">/</span><span class="org-highlight-numbers-number">1000</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span><span class="org-type">/</span><span class="org-highlight-numbers-number">6</span>; <span class="org-comment">% TODO [kg]</span>
|
|
Leg = updateDamping<span class="org-rainbow-delimiters-depth-1">(</span>Leg<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Sphere</span></span>
|
|
SP = struct<span class="org-rainbow-delimiters-depth-1">()</span>;
|
|
|
|
SP.height.bottom = <span class="org-highlight-numbers-number">27</span>; <span class="org-comment">% [mm]</span>
|
|
SP.height.top = <span class="org-highlight-numbers-number">27</span>; <span class="org-comment">% [mm]</span>
|
|
SP.density.bottom = <span class="org-highlight-numbers-number">8000</span>; % [kg<span class="org-type">/</span>m<span class="org-type">^</span><span class="org-highlight-numbers-number">3</span>]
|
|
SP.density.top = <span class="org-highlight-numbers-number">8000</span>; % [kg<span class="org-type">/</span>m<span class="org-type">^</span><span class="org-highlight-numbers-number">3</span>]
|
|
SP.color.bottom = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">6</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">6</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">6</span><span class="org-rainbow-delimiters-depth-1">]</span>; <span class="org-comment">% [rgb]</span>
|
|
SP.color.top = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">6</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">6</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">6</span><span class="org-rainbow-delimiters-depth-1">]</span>; <span class="org-comment">% [rgb]</span>
|
|
SP.k.ax = <span class="org-highlight-numbers-number">0</span>; <span class="org-comment">% [N*m/deg]</span>
|
|
SP.ksi.ax = <span class="org-highlight-numbers-number">10</span>;
|
|
|
|
SP.thickness.bottom = SP.height.bottom<span class="org-type">-</span>Leg.sphere.bottom; <span class="org-comment">% [mm]</span>
|
|
SP.thickness.top = SP.height.top<span class="org-type">-</span>Leg.sphere.top; <span class="org-comment">% [mm]</span>
|
|
SP.rad.bottom = Leg.sphere.bottom; <span class="org-comment">% [mm]</span>
|
|
SP.rad.top = Leg.sphere.top; <span class="org-comment">% [mm]</span>
|
|
SP.m = SP.density.bottom<span class="org-type">*</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><span class="org-rainbow-delimiters-depth-1">(</span><span class="org-rainbow-delimiters-depth-2">(</span>SP.rad.bottom<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-rainbow-delimiters-depth-2">)</span><span class="org-type">^</span><span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-1">)</span><span class="org-type">*</span><span class="org-rainbow-delimiters-depth-1">(</span>SP.height.bottom<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-rainbow-delimiters-depth-1">)</span>; <span class="org-comment">% TODO [kg]</span>
|
|
|
|
SP = updateDamping<span class="org-rainbow-delimiters-depth-1">(</span>SP<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%%</span></span>
|
|
Leg.support.bottom = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span> SP.thickness.bottom; <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span>; SP.rad.bottom <span class="org-highlight-numbers-number">0</span>; SP.rad.bottom SP.height.bottom<span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
Leg.support.top = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span> SP.thickness.top; <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span>; SP.rad.top <span class="org-highlight-numbers-number">0</span>; SP.rad.top SP.height.top<span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%%</span></span>
|
|
micro_hexapod.BP = BP;
|
|
micro_hexapod.TP = TP;
|
|
micro_hexapod.Leg = Leg;
|
|
micro_hexapod.SP = SP;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%%</span></span>
|
|
micro_hexapod = initializeParameters<span class="org-rainbow-delimiters-depth-1">(</span>micro_hexapod<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Setup equilibrium position of each leg</span></span>
|
|
micro_hexapod.L0 = inverseKinematicsHexapod<span class="org-rainbow-delimiters-depth-1">(</span>micro_hexapod, opts.AP, opts.ARB<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Save</span></span>
|
|
save<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'./mat/stages.mat'</span>, <span class="org-string">'micro_hexapod'</span>, <span class="org-string">'-append'</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%%</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">element</span><span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">]</span></span> = <span class="org-function-name">updateDamping</span><span class="org-rainbow-delimiters-depth-1">(</span><span class="org-variable-name">element</span><span class="org-rainbow-delimiters-depth-1">)</span>
|
|
field = fieldnames<span class="org-rainbow-delimiters-depth-1">(</span>element.k<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">field</span><span class="org-constant"><span class="org-rainbow-delimiters-depth-1">)</span></span>
|
|
element.c.<span class="org-rainbow-delimiters-depth-1">(</span>field<span class="org-rainbow-delimiters-depth-2">{</span><span class="org-constant">i</span><span class="org-rainbow-delimiters-depth-2">}</span><span class="org-rainbow-delimiters-depth-1">)</span> = <span class="org-highlight-numbers-number">2</span><span class="org-type">*</span>element.ksi.<span class="org-rainbow-delimiters-depth-1">(</span>field<span class="org-rainbow-delimiters-depth-2">{</span><span class="org-constant">i</span><span class="org-rainbow-delimiters-depth-2">}</span><span class="org-rainbow-delimiters-depth-1">)</span><span class="org-type">*</span>sqrt<span class="org-rainbow-delimiters-depth-1">(</span>element.k.<span class="org-rainbow-delimiters-depth-2">(</span>field<span class="org-rainbow-delimiters-depth-3">{</span><span class="org-constant">i</span><span class="org-rainbow-delimiters-depth-3">}</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">*</span>element.m<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">%%</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">stewart</span><span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">]</span></span> = <span class="org-function-name">initializeParameters</span><span class="org-rainbow-delimiters-depth-1">(</span><span class="org-variable-name">stewart</span><span class="org-rainbow-delimiters-depth-1">)</span>
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Connection points on base and top plate w.r.t. World frame at the center of the base plate</span></span>
|
|
stewart.pos_base = zeros<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">6</span>, <span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
stewart.pos_top = zeros<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">6</span>, <span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
alpha_b = stewart.BP.leg.ang<span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">/</span><span class="org-highlight-numbers-number">180</span>; % angle de décalage par rapport à <span class="org-highlight-numbers-number">120</span> deg (pour positionner les supports bases)
|
|
alpha_t = stewart.TP.leg.ang<span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">/</span><span class="org-highlight-numbers-number">180</span>; % <span class="org-type">+-</span> offset angle from <span class="org-highlight-numbers-number">120</span> degree spacing on top
|
|
|
|
height = <span class="org-rainbow-delimiters-depth-1">(</span>stewart.h<span class="org-type">-</span>stewart.BP.thickness<span class="org-type">-</span>stewart.TP.thickness<span class="org-type">-</span>stewart.Leg.sphere.bottom<span class="org-type">-</span>stewart.Leg.sphere.top<span class="org-type">-</span>stewart.SP.thickness.bottom<span class="org-type">-</span>stewart.SP.thickness.top<span class="org-rainbow-delimiters-depth-1">)</span><span class="org-type">*</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">001</span>; <span class="org-comment">% TODO</span>
|
|
|
|
radius_b = stewart.BP.leg.rad<span class="org-type">*</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">001</span>; <span class="org-comment">% rayon emplacement support base</span>
|
|
radius_t = stewart.TP.leg.rad<span class="org-type">*</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">001</span>; <span class="org-comment">% top radius in meters</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">3</span></span>
|
|
<span class="org-comment">% base points</span>
|
|
angle_m_b = <span class="org-rainbow-delimiters-depth-1">(</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><span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-1">)</span><span class="org-type">*</span> <span class="org-rainbow-delimiters-depth-1">(</span><span class="org-constant">i</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">-</span> alpha_b;
|
|
angle_p_b = <span class="org-rainbow-delimiters-depth-1">(</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><span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-1">)</span><span class="org-type">*</span> <span class="org-rainbow-delimiters-depth-1">(</span><span class="org-constant">i</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">+</span> alpha_b;
|
|
stewart.pos_base<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">2</span><span class="org-type">*</span><span class="org-constant">i</span><span class="org-type">-</span><span class="org-highlight-numbers-number">1</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-1">)</span> = <span class="org-rainbow-delimiters-depth-1">[</span>radius_b<span class="org-type">*</span>cos<span class="org-rainbow-delimiters-depth-2">(</span>angle_m_b<span class="org-rainbow-delimiters-depth-2">)</span>, radius_b<span class="org-type">*</span>sin<span class="org-rainbow-delimiters-depth-2">(</span>angle_m_b<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-rainbow-delimiters-depth-1">]</span>;
|
|
stewart.pos_base<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">2</span><span class="org-type">*</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-1">)</span> = <span class="org-rainbow-delimiters-depth-1">[</span>radius_b<span class="org-type">*</span>cos<span class="org-rainbow-delimiters-depth-2">(</span>angle_p_b<span class="org-rainbow-delimiters-depth-2">)</span>, radius_b<span class="org-type">*</span>sin<span class="org-rainbow-delimiters-depth-2">(</span>angle_p_b<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-rainbow-delimiters-depth-1">]</span>;
|
|
|
|
<span class="org-comment">% top points</span>
|
|
% Top points are <span class="org-highlight-numbers-number">60</span> degrees offset
|
|
angle_m_t = <span class="org-rainbow-delimiters-depth-1">(</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><span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-1">)</span><span class="org-type">*</span> <span class="org-rainbow-delimiters-depth-1">(</span><span class="org-constant">i</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">-</span> alpha_t <span class="org-type">+</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><span class="org-highlight-numbers-number">6</span>;
|
|
angle_p_t = <span class="org-rainbow-delimiters-depth-1">(</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><span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-1">)</span><span class="org-type">*</span> <span class="org-rainbow-delimiters-depth-1">(</span><span class="org-constant">i</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">+</span> alpha_t <span class="org-type">+</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><span class="org-highlight-numbers-number">6</span>;
|
|
stewart.pos_top<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">2</span><span class="org-type">*</span><span class="org-constant">i</span><span class="org-type">-</span><span class="org-highlight-numbers-number">1</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-1">)</span> = <span class="org-rainbow-delimiters-depth-1">[</span>radius_t<span class="org-type">*</span>cos<span class="org-rainbow-delimiters-depth-2">(</span>angle_m_t<span class="org-rainbow-delimiters-depth-2">)</span>, radius_t<span class="org-type">*</span>sin<span class="org-rainbow-delimiters-depth-2">(</span>angle_m_t<span class="org-rainbow-delimiters-depth-2">)</span>, height<span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
stewart.pos_top<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">2</span><span class="org-type">*</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-1">)</span> = <span class="org-rainbow-delimiters-depth-1">[</span>radius_t<span class="org-type">*</span>cos<span class="org-rainbow-delimiters-depth-2">(</span>angle_p_t<span class="org-rainbow-delimiters-depth-2">)</span>, radius_t<span class="org-type">*</span>sin<span class="org-rainbow-delimiters-depth-2">(</span>angle_p_t<span class="org-rainbow-delimiters-depth-2">)</span>, height<span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
<span class="org-keyword">end</span>
|
|
|
|
<span class="org-comment">% permute pos_top points so that legs are end points of base and top points</span>
|
|
stewart.pos_top = <span class="org-rainbow-delimiters-depth-1">[</span>stewart.pos_top<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">6</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span>; stewart.pos_top<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">5</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">]</span>; %<span class="org-highlight-numbers-number">6th</span> point on top connects to <span class="org-highlight-numbers-number">1st</span> on bottom
|
|
stewart.pos_top_tranform = stewart.pos_top <span class="org-type">-</span> height<span class="org-type">*</span><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-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-2">)</span>,ones<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">6</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-matlab-cellbreak"><span class="org-comment">%% leg vectors</span></span>
|
|
legs = stewart.pos_top <span class="org-type">-</span> stewart.pos_base;
|
|
leg_length = 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>;
|
|
leg_vectors = zeros<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">6</span>, <span class="org-highlight-numbers-number">3</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>
|
|
leg_length<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-constant">i</span><span class="org-rainbow-delimiters-depth-1">)</span> = norm<span class="org-rainbow-delimiters-depth-1">(</span>legs<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
leg_vectors<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> = legs<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> leg_length<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-constant">i</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
<span class="org-keyword">end</span>
|
|
|
|
stewart.Leg.lenght = <span class="org-highlight-numbers-number">1000</span><span class="org-type">*</span>leg_length<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><span class="org-highlight-numbers-number">1</span>.<span class="org-highlight-numbers-number">5</span>;
|
|
stewart.Leg.shape.bot = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span>; ...
|
|
stewart.Leg.rad.bottom <span class="org-highlight-numbers-number">0</span>; ...
|
|
stewart.Leg.rad.bottom stewart.Leg.lenght; ...
|
|
stewart.Leg.rad.top stewart.Leg.lenght; ...
|
|
stewart.Leg.rad.top <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">2</span><span class="org-type">*</span>stewart.Leg.lenght; ...
|
|
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">2</span><span class="org-type">*</span>stewart.Leg.lenght<span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Calculate revolute and cylindrical axes</span></span>
|
|
rev1 = zeros<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">6</span>, <span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
rev2 = zeros<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">6</span>, <span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
cyl1 = zeros<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">6</span>, <span class="org-highlight-numbers-number">3</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>
|
|
rev1<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> = cross<span class="org-rainbow-delimiters-depth-1">(</span>leg_vectors<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-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><span class="org-rainbow-delimiters-depth-2">]</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
rev1<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> = rev1<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> norm<span class="org-rainbow-delimiters-depth-1">(</span>rev1<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
rev2<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> cross<span class="org-rainbow-delimiters-depth-1">(</span>rev1<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span>, leg_vectors<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
rev2<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> = rev2<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> norm<span class="org-rainbow-delimiters-depth-1">(</span>rev2<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
cyl1<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> = leg_vectors<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-keyword">end</span>
|
|
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Coordinate systems</span></span>
|
|
stewart.lower_leg = struct<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'rotation'</span>, eye<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-rainbow-delimiters-depth-1">)</span>;
|
|
stewart.upper_leg = struct<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'rotation'</span>, eye<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-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>
|
|
stewart.lower_leg<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-constant">i</span><span class="org-rainbow-delimiters-depth-1">)</span>.rotation = <span class="org-rainbow-delimiters-depth-1">[</span>rev1<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">'</span>, rev2<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">'</span>, cyl1<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">'</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
stewart.upper_leg<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-constant">i</span><span class="org-rainbow-delimiters-depth-1">)</span>.rotation = <span class="org-rainbow-delimiters-depth-1">[</span>rev1<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">'</span>, rev2<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">'</span>, cyl1<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">'</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
<span class="org-keyword">end</span>
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Position Matrix</span></span>
|
|
stewart.M_pos_base = stewart.pos_base <span class="org-type">+</span> <span class="org-rainbow-delimiters-depth-1">(</span>height<span class="org-type">+</span><span class="org-rainbow-delimiters-depth-2">(</span>stewart.TP.thickness<span class="org-type">+</span>stewart.Leg.sphere.top<span class="org-type">+</span>stewart.SP.thickness.top<span class="org-type">+</span>stewart.jacobian<span class="org-rainbow-delimiters-depth-2">)</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-rainbow-delimiters-depth-1">)</span><span class="org-type">*</span><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-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-2">)</span>,ones<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">6</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-matlab-cellbreak"><span class="org-comment">%% Compute Jacobian Matrix</span></span>
|
|
aa = stewart.pos_top_tranform <span class="org-type">+</span> <span class="org-rainbow-delimiters-depth-1">(</span>stewart.jacobian <span class="org-type">-</span> stewart.TP.thickness <span class="org-type">-</span> stewart.SP.height.top<span class="org-rainbow-delimiters-depth-1">)</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>zeros<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">6</span>, <span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-2">)</span>,ones<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">6</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>;
|
|
stewart.J = getJacobianMatrix<span class="org-rainbow-delimiters-depth-1">(</span>leg_vectors<span class="org-type">'</span>, aa<span class="org-type">'</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
<span class="org-keyword">end</span>
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%%</span></span>
|
|
<span class="org-keyword">function</span> <span class="org-variable-name">J</span> = <span class="org-function-name">getJacobianMatrix</span><span class="org-rainbow-delimiters-depth-1">(</span><span class="org-variable-name">RM</span>, <span class="org-variable-name">M_pos_base</span><span class="org-rainbow-delimiters-depth-1">)</span>
|
|
% RM<span class="org-type">:</span> [<span class="org-highlight-numbers-number">3x6</span>] unit vector of each leg in the fixed frame
|
|
% M_pos_base<span class="org-type">:</span> [<span class="org-highlight-numbers-number">3x6</span>] vector of the leg connection at the top platform location in the fixed frame
|
|
J = zeros<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">6</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
J<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-type">:</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> = RM<span class="org-type">'</span>;
|
|
J<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-type">:</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> = cross<span class="org-rainbow-delimiters-depth-1">(</span>M_pos_base, RM<span class="org-rainbow-delimiters-depth-1">)</span><span class="org-type">'</span>;
|
|
<span class="org-keyword">end</span>
|
|
<span class="org-keyword">end</span>
|
|
</pre>
|
|
</div>
|
|
</div>
|
|
</div>
|
|
|
|
<div id="outline-container-org263aa9c" class="outline-3">
|
|
<h3 id="org263aa9c"><span class="section-number-3">2.7</span> Center of gravity compensation</h3>
|
|
<div class="outline-text-3" id="text-2-7">
|
|
<p>
|
|
<a id="org50c8365"></a>
|
|
</p>
|
|
|
|
<p>
|
|
This Matlab function is accessible <a href="../src/initializeAxisc.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">axisc</span><span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">]</span></span> = <span class="org-function-name">initializeAxisc</span><span class="org-rainbow-delimiters-depth-1">()</span>
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%%</span></span>
|
|
axisc = struct<span class="org-rainbow-delimiters-depth-1">()</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Axis Compensator - Static Properties</span></span>
|
|
<span class="org-comment">% Structure</span>
|
|
axisc.structure.density = <span class="org-highlight-numbers-number">3400</span>; <span class="org-comment">% [kg/m3]</span>
|
|
axisc.structure.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">792</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">820</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">933</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
axisc.structure.STEP = <span class="org-string">'./STEPS/axisc/axisc_structure.STEP'</span>;
|
|
<span class="org-comment">% Wheel</span>
|
|
axisc.wheel.density = <span class="org-highlight-numbers-number">2700</span>; <span class="org-comment">% [kg/m3]</span>
|
|
axisc.wheel.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">753</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">753</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">753</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
axisc.wheel.STEP = <span class="org-string">'./STEPS/axisc/axisc_wheel.STEP'</span>;
|
|
<span class="org-comment">% Mass</span>
|
|
axisc.mass.density = <span class="org-highlight-numbers-number">7800</span>; <span class="org-comment">% [kg/m3]</span>
|
|
axisc.mass.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">792</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">820</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">933</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
axisc.mass.STEP = <span class="org-string">'./STEPS/axisc/axisc_mass.STEP'</span>;
|
|
<span class="org-comment">% Gear</span>
|
|
axisc.gear.density = <span class="org-highlight-numbers-number">7800</span>; <span class="org-comment">% [kg/m3]</span>
|
|
axisc.gear.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">792</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">820</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">933</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
axisc.gear.STEP = <span class="org-string">'./STEPS/axisc/axisc_gear.STEP'</span>;
|
|
|
|
axisc.m = <span class="org-highlight-numbers-number">40</span>; <span class="org-comment">% TODO [kg]</span>
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Axis Compensator - Dynamical Properties</span></span>
|
|
% axisc.k.ax = <span class="org-highlight-numbers-number">1</span>; % TODO [N<span class="org-type">*</span>m<span class="org-type">/</span>deg)]
|
|
% axisc.c.ax = (<span class="org-highlight-numbers-number">1</span><span class="org-type">/</span><span class="org-highlight-numbers-number">1</span>)<span class="org-type">*</span>sqrt(axisc.k.ax<span class="org-type">/</span>axisc.m);
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Save</span></span>
|
|
save<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'./mat/stages.mat'</span>, <span class="org-string">'axisc'</span>, <span class="org-string">'-append'</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
<span class="org-keyword">end</span>
|
|
</pre>
|
|
</div>
|
|
</div>
|
|
</div>
|
|
|
|
<div id="outline-container-org125d09f" class="outline-3">
|
|
<h3 id="org125d09f"><span class="section-number-3">2.8</span> Mirror</h3>
|
|
<div class="outline-text-3" id="text-2-8">
|
|
<p>
|
|
<a id="orgebf22ee"></a>
|
|
</p>
|
|
|
|
<p>
|
|
This Matlab function is accessible <a href="../src/initializeMirror.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">initializeMirror</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-string">'shape'</span>, <span class="org-string">'spherical'</span>, ...<span class="org-comment"> % spherical or conical</span>
|
|
<span class="org-string">'angle'</span>, <span class="org-highlight-numbers-number">45</span> ...
|
|
<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">%%</span></span>
|
|
mirror = struct<span class="org-rainbow-delimiters-depth-1">()</span>;
|
|
mirror.h = <span class="org-highlight-numbers-number">50</span>; <span class="org-comment">% height of the mirror [mm]</span>
|
|
mirror.thickness = <span class="org-highlight-numbers-number">25</span>; <span class="org-comment">% Thickness of the plate supporting the sample [mm]</span>
|
|
mirror.hole_rad = <span class="org-highlight-numbers-number">120</span>; <span class="org-comment">% radius of the hole in the mirror [mm]</span>
|
|
mirror.support_rad = <span class="org-highlight-numbers-number">100</span>; <span class="org-comment">% radius of the support plate [mm]</span>
|
|
mirror.jacobian = <span class="org-highlight-numbers-number">150</span>; <span class="org-comment">% point of interest offset in z (above the top surfave) [mm]</span>
|
|
mirror.rad = <span class="org-highlight-numbers-number">180</span>; <span class="org-comment">% radius of the mirror (at the bottom surface) [mm]</span>
|
|
|
|
mirror.density = <span class="org-highlight-numbers-number">2400</span>; <span class="org-comment">% Density of the mirror [kg/m3]</span>
|
|
mirror.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">4</span> <span class="org-highlight-numbers-number">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-rainbow-delimiters-depth-1">]</span>; <span class="org-comment">% Color of the mirror</span>
|
|
|
|
mirror.cone_length = mirror.rad<span class="org-type">*</span>tand<span class="org-rainbow-delimiters-depth-1">(</span>opts.angle<span class="org-rainbow-delimiters-depth-1">)</span><span class="org-type">+</span>mirror.h<span class="org-type">+</span>mirror.jacobian; <span class="org-comment">% Distance from Apex point of the cone to jacobian point</span>
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Shape</span></span>
|
|
mirror.shape = <span class="org-rainbow-delimiters-depth-1">[</span>...
|
|
<span class="org-highlight-numbers-number">0</span> mirror.h<span class="org-type">-</span>mirror.thickness
|
|
mirror.hole_rad mirror.h<span class="org-type">-</span>mirror.thickness; ...
|
|
mirror.hole_rad <span class="org-highlight-numbers-number">0</span>; ...
|
|
mirror.rad <span class="org-highlight-numbers-number">0</span> ...
|
|
<span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
|
|
<span class="org-keyword">if</span> strcmp<span class="org-rainbow-delimiters-depth-1">(</span>opts.shape, <span class="org-string">'spherical'</span><span class="org-rainbow-delimiters-depth-1">)</span>
|
|
mirror.sphere_radius = sqrt<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-rainbow-delimiters-depth-2">(</span>mirror.jacobian<span class="org-type">+</span>mirror.h<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>mirror.rad<span class="org-type">^</span><span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-1">)</span>; <span class="org-comment">% Radius of the sphere [mm]</span>
|
|
|
|
<span class="org-keyword">for</span> <span class="org-variable-name">z</span> = <span class="org-constant">linspace</span><span class="org-constant"><span class="org-rainbow-delimiters-depth-1">(</span></span><span class="org-constant"><span class="org-highlight-numbers-number">0</span></span><span class="org-constant">, mirror.h, </span><span class="org-constant"><span class="org-highlight-numbers-number">101</span></span><span class="org-constant"><span class="org-rainbow-delimiters-depth-1">)</span></span>
|
|
mirror.shape = <span class="org-rainbow-delimiters-depth-1">[</span>mirror.shape; sqrt<span class="org-rainbow-delimiters-depth-2">(</span>mirror.sphere_radius<span class="org-type">^</span><span class="org-highlight-numbers-number">2</span><span class="org-type">-</span><span class="org-rainbow-delimiters-depth-3">(</span>z<span class="org-type">-</span>mirror.jacobian<span class="org-type">-</span>mirror.h<span class="org-rainbow-delimiters-depth-3">)</span><span class="org-type">^</span><span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-2">)</span> z<span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
<span class="org-keyword">end</span>
|
|
<span class="org-keyword">elseif</span> strcmp<span class="org-rainbow-delimiters-depth-1">(</span>opts.shape, <span class="org-string">'conical'</span><span class="org-rainbow-delimiters-depth-1">)</span>
|
|
mirror.shape = <span class="org-rainbow-delimiters-depth-1">[</span>mirror.shape; mirror.rad<span class="org-type">+</span>mirror.h<span class="org-type">/</span>tand<span class="org-rainbow-delimiters-depth-2">(</span>opts.angle<span class="org-rainbow-delimiters-depth-2">)</span> mirror.h<span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
<span class="org-keyword">else</span>
|
|
error<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'Shape should be either conical or spherical'</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
<span class="org-keyword">end</span>
|
|
|
|
mirror.shape = <span class="org-rainbow-delimiters-depth-1">[</span>mirror.shape; <span class="org-highlight-numbers-number">0</span> mirror.h<span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Save</span></span>
|
|
save<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'./mat/stages.mat'</span>, <span class="org-string">'mirror'</span>, <span class="org-string">'-append'</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
<span class="org-keyword">end</span>
|
|
</pre>
|
|
</div>
|
|
</div>
|
|
</div>
|
|
|
|
<div id="outline-container-orgf1edf76" class="outline-3">
|
|
<h3 id="orgf1edf76"><span class="section-number-3">2.9</span> Nano Hexapod</h3>
|
|
<div class="outline-text-3" id="text-2-9">
|
|
<p>
|
|
<a id="org371306e"></a>
|
|
</p>
|
|
|
|
<p>
|
|
This Matlab function is accessible <a href="../src/initializeNanoHexapod.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">nano_hexapod</span><span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">]</span></span> = <span class="org-function-name">initializeNanoHexapod</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-string">'actuator'</span>, <span class="org-string">'piezo'</span><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">%% Stewart Object</span></span>
|
|
nano_hexapod = struct<span class="org-rainbow-delimiters-depth-1">()</span>;
|
|
nano_hexapod.h = <span class="org-highlight-numbers-number">90</span>; <span class="org-comment">% Total height of the platform [mm]</span>
|
|
nano_hexapod.jacobian = <span class="org-highlight-numbers-number">175</span>; <span class="org-comment">% Point where the Jacobian is computed => Center of rotation [mm]</span>
|
|
% nano_hexapod.jacobian = <span class="org-highlight-numbers-number">174</span>.<span class="org-highlight-numbers-number">26</span>; % Point where the Jacobian is computed =<span class="org-type">></span> Center of rotation [mm]
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Bottom Plate</span></span>
|
|
BP = struct<span class="org-rainbow-delimiters-depth-1">()</span>;
|
|
|
|
BP.rad.int = <span class="org-highlight-numbers-number">0</span>; <span class="org-comment">% Internal Radius [mm]</span>
|
|
BP.rad.ext = <span class="org-highlight-numbers-number">150</span>; <span class="org-comment">% External Radius [mm]</span>
|
|
BP.thickness = <span class="org-highlight-numbers-number">10</span>; <span class="org-comment">% Thickness [mm]</span>
|
|
BP.leg.rad = <span class="org-highlight-numbers-number">100</span>; <span class="org-comment">% Radius where the legs articulations are positionned [mm]</span>
|
|
BP.leg.ang = <span class="org-highlight-numbers-number">5</span>; <span class="org-comment">% Angle Offset [deg]</span>
|
|
BP.density = <span class="org-highlight-numbers-number">8000</span>;% Density of the material [kg<span class="org-type">/</span>m<span class="org-type">^</span><span class="org-highlight-numbers-number">3</span>]
|
|
BP.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">7</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">7</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">7</span><span class="org-rainbow-delimiters-depth-1">]</span>; <span class="org-comment">% Color [rgb]</span>
|
|
BP.shape = <span class="org-rainbow-delimiters-depth-1">[</span>BP.rad.int BP.thickness; BP.rad.int <span class="org-highlight-numbers-number">0</span>; BP.rad.ext <span class="org-highlight-numbers-number">0</span>; BP.rad.ext BP.thickness<span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Top Plate</span></span>
|
|
TP = struct<span class="org-rainbow-delimiters-depth-1">()</span>;
|
|
|
|
TP.rad.int = <span class="org-highlight-numbers-number">0</span>; <span class="org-comment">% Internal Radius [mm]</span>
|
|
TP.rad.ext = <span class="org-highlight-numbers-number">100</span>; <span class="org-comment">% Internal Radius [mm]</span>
|
|
TP.thickness = <span class="org-highlight-numbers-number">10</span>; <span class="org-comment">% Thickness [mm]</span>
|
|
TP.leg.rad = <span class="org-highlight-numbers-number">90</span>; <span class="org-comment">% Radius where the legs articulations are positionned [mm]</span>
|
|
TP.leg.ang = <span class="org-highlight-numbers-number">5</span>; <span class="org-comment">% Angle Offset [deg]</span>
|
|
TP.density = <span class="org-highlight-numbers-number">8000</span>;% Density of the material [kg<span class="org-type">/</span>m<span class="org-type">^</span><span class="org-highlight-numbers-number">3</span>]
|
|
TP.color = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">7</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">7</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">7</span><span class="org-rainbow-delimiters-depth-1">]</span>; <span class="org-comment">% Color [rgb]</span>
|
|
TP.shape = <span class="org-rainbow-delimiters-depth-1">[</span>TP.rad.int TP.thickness; TP.rad.int <span class="org-highlight-numbers-number">0</span>; TP.rad.ext <span class="org-highlight-numbers-number">0</span>; TP.rad.ext TP.thickness<span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Leg</span></span>
|
|
Leg = struct<span class="org-rainbow-delimiters-depth-1">()</span>;
|
|
|
|
Leg.stroke = <span class="org-highlight-numbers-number">80e</span><span class="org-type">-</span><span class="org-highlight-numbers-number">6</span>; <span class="org-comment">% Maximum Stroke of each leg [m]</span>
|
|
<span class="org-keyword">if</span> strcmp<span class="org-rainbow-delimiters-depth-1">(</span>opts.actuator, <span class="org-string">'piezo'</span><span class="org-rainbow-delimiters-depth-1">)</span>
|
|
Leg.k.ax = <span class="org-highlight-numbers-number">1e7</span>; <span class="org-comment">% Stiffness of each leg [N/m]</span>
|
|
<span class="org-keyword">elseif</span> strcmp<span class="org-rainbow-delimiters-depth-1">(</span>opts.actuator, <span class="org-string">'lorentz'</span><span class="org-rainbow-delimiters-depth-1">)</span>
|
|
Leg.k.ax = <span class="org-highlight-numbers-number">1e4</span>; <span class="org-comment">% Stiffness of each leg [N/m]</span>
|
|
<span class="org-keyword">else</span>
|
|
error<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'opts.actuator should be piezo or lorentz'</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
<span class="org-keyword">end</span>
|
|
Leg.ksi.ax = <span class="org-highlight-numbers-number">10</span>; <span class="org-comment">% Maximum amplification at resonance []</span>
|
|
Leg.rad.bottom = <span class="org-highlight-numbers-number">12</span>; <span class="org-comment">% Radius of the cylinder of the bottom part [mm]</span>
|
|
Leg.rad.top = <span class="org-highlight-numbers-number">10</span>; <span class="org-comment">% Radius of the cylinder of the top part [mm]</span>
|
|
Leg.density = <span class="org-highlight-numbers-number">8000</span>; % Density of the material [kg<span class="org-type">/</span>m<span class="org-type">^</span><span class="org-highlight-numbers-number">3</span>]
|
|
Leg.color.bottom = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">5</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">5</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">5</span><span class="org-rainbow-delimiters-depth-1">]</span>; <span class="org-comment">% Color [rgb]</span>
|
|
Leg.color.top = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">5</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">5</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">5</span><span class="org-rainbow-delimiters-depth-1">]</span>; <span class="org-comment">% Color [rgb]</span>
|
|
|
|
Leg.sphere.bottom = Leg.rad.bottom; <span class="org-comment">% Size of the sphere at the end of the leg [mm]</span>
|
|
Leg.sphere.top = Leg.rad.top; <span class="org-comment">% Size of the sphere at the end of the leg [mm]</span>
|
|
Leg.m = TP.density<span class="org-type">*</span><span class="org-rainbow-delimiters-depth-1">(</span><span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">pi</span><span class="org-type">*</span><span class="org-rainbow-delimiters-depth-3">(</span>TP.rad.ext<span class="org-type">/</span><span class="org-highlight-numbers-number">1000</span><span class="org-rainbow-delimiters-depth-3">)</span><span class="org-type">^</span><span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">*</span><span class="org-rainbow-delimiters-depth-2">(</span>TP.thickness<span class="org-type">/</span><span class="org-highlight-numbers-number">1000</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">-</span><span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">pi</span><span class="org-type">*</span><span class="org-rainbow-delimiters-depth-3">(</span>TP.rad.int<span class="org-type">/</span><span class="org-highlight-numbers-number">1000</span><span class="org-type">^</span><span class="org-highlight-numbers-number">2</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-rainbow-delimiters-depth-2">(</span>TP.thickness<span class="org-type">/</span><span class="org-highlight-numbers-number">1000</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span><span class="org-type">/</span><span class="org-highlight-numbers-number">6</span>; <span class="org-comment">% TODO [kg]</span>
|
|
|
|
Leg = updateDamping<span class="org-rainbow-delimiters-depth-1">(</span>Leg<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Sphere</span></span>
|
|
SP = struct<span class="org-rainbow-delimiters-depth-1">()</span>;
|
|
|
|
SP.height.bottom = <span class="org-highlight-numbers-number">15</span>; <span class="org-comment">% [mm]</span>
|
|
SP.height.top = <span class="org-highlight-numbers-number">15</span>; <span class="org-comment">% [mm]</span>
|
|
SP.density.bottom = <span class="org-highlight-numbers-number">8000</span>; % [kg<span class="org-type">/</span>m<span class="org-type">^</span><span class="org-highlight-numbers-number">3</span>]
|
|
SP.density.top = <span class="org-highlight-numbers-number">8000</span>; % [kg<span class="org-type">/</span>m<span class="org-type">^</span><span class="org-highlight-numbers-number">3</span>]
|
|
SP.color.bottom = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">7</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">7</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">7</span><span class="org-rainbow-delimiters-depth-1">]</span>; <span class="org-comment">% [rgb]</span>
|
|
SP.color.top = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">7</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">7</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">7</span><span class="org-rainbow-delimiters-depth-1">]</span>; <span class="org-comment">% [rgb]</span>
|
|
SP.k.ax = <span class="org-highlight-numbers-number">0</span>; <span class="org-comment">% [N*m/deg]</span>
|
|
SP.ksi.ax = <span class="org-highlight-numbers-number">0</span>;
|
|
|
|
SP.thickness.bottom = SP.height.bottom<span class="org-type">-</span>Leg.sphere.bottom; <span class="org-comment">% [mm]</span>
|
|
SP.thickness.top = SP.height.top<span class="org-type">-</span>Leg.sphere.top; <span class="org-comment">% [mm]</span>
|
|
SP.rad.bottom = Leg.sphere.bottom; <span class="org-comment">% [mm]</span>
|
|
SP.rad.top = Leg.sphere.top; <span class="org-comment">% [mm]</span>
|
|
SP.m = SP.density.bottom<span class="org-type">*</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><span class="org-rainbow-delimiters-depth-1">(</span><span class="org-rainbow-delimiters-depth-2">(</span>SP.rad.bottom<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-rainbow-delimiters-depth-2">)</span><span class="org-type">^</span><span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-1">)</span><span class="org-type">*</span><span class="org-rainbow-delimiters-depth-1">(</span>SP.height.bottom<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-rainbow-delimiters-depth-1">)</span>; <span class="org-comment">% TODO [kg]</span>
|
|
|
|
SP = updateDamping<span class="org-rainbow-delimiters-depth-1">(</span>SP<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%%</span></span>
|
|
Leg.support.bottom = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span> SP.thickness.bottom; <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span>; SP.rad.bottom <span class="org-highlight-numbers-number">0</span>; SP.rad.bottom SP.height.bottom<span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
Leg.support.top = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span> SP.thickness.top; <span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span>; SP.rad.top <span class="org-highlight-numbers-number">0</span>; SP.rad.top SP.height.top<span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%%</span></span>
|
|
nano_hexapod.BP = BP;
|
|
nano_hexapod.TP = TP;
|
|
nano_hexapod.Leg = Leg;
|
|
nano_hexapod.SP = SP;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%%</span></span>
|
|
nano_hexapod = initializeParameters<span class="org-rainbow-delimiters-depth-1">(</span>nano_hexapod<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Save</span></span>
|
|
save<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'./mat/stages.mat'</span>, <span class="org-string">'nano_hexapod'</span>, <span class="org-string">'-append'</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%%</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">element</span><span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">]</span></span> = <span class="org-function-name">updateDamping</span><span class="org-rainbow-delimiters-depth-1">(</span><span class="org-variable-name">element</span><span class="org-rainbow-delimiters-depth-1">)</span>
|
|
field = fieldnames<span class="org-rainbow-delimiters-depth-1">(</span>element.k<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">field</span><span class="org-constant"><span class="org-rainbow-delimiters-depth-1">)</span></span>
|
|
<span class="org-keyword">if</span> element.ksi.<span class="org-rainbow-delimiters-depth-1">(</span>field<span class="org-rainbow-delimiters-depth-2">{</span><span class="org-constant">i</span><span class="org-rainbow-delimiters-depth-2">}</span><span class="org-rainbow-delimiters-depth-1">)</span> <span class="org-type">></span> <span class="org-highlight-numbers-number">0</span>
|
|
element.c.<span class="org-rainbow-delimiters-depth-1">(</span>field<span class="org-rainbow-delimiters-depth-2">{</span><span class="org-constant">i</span><span class="org-rainbow-delimiters-depth-2">}</span><span class="org-rainbow-delimiters-depth-1">)</span> = <span class="org-highlight-numbers-number">1</span><span class="org-type">/</span>element.ksi.<span class="org-rainbow-delimiters-depth-1">(</span>field<span class="org-rainbow-delimiters-depth-2">{</span><span class="org-constant">i</span><span class="org-rainbow-delimiters-depth-2">}</span><span class="org-rainbow-delimiters-depth-1">)</span><span class="org-type">*</span>sqrt<span class="org-rainbow-delimiters-depth-1">(</span>element.k.<span class="org-rainbow-delimiters-depth-2">(</span>field<span class="org-rainbow-delimiters-depth-3">{</span><span class="org-constant">i</span><span class="org-rainbow-delimiters-depth-3">}</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">/</span>element.m<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
<span class="org-keyword">else</span>
|
|
element.c.<span class="org-rainbow-delimiters-depth-1">(</span>field<span class="org-rainbow-delimiters-depth-2">{</span><span class="org-constant">i</span><span class="org-rainbow-delimiters-depth-2">}</span><span class="org-rainbow-delimiters-depth-1">)</span> = <span class="org-highlight-numbers-number">0</span>;
|
|
<span class="org-keyword">end</span>
|
|
<span class="org-keyword">end</span>
|
|
<span class="org-keyword">end</span>
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%%</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">stewart</span><span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">]</span></span> = <span class="org-function-name">initializeParameters</span><span class="org-rainbow-delimiters-depth-1">(</span><span class="org-variable-name">stewart</span><span class="org-rainbow-delimiters-depth-1">)</span>
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Connection points on base and top plate w.r.t. World frame at the center of the base plate</span></span>
|
|
stewart.pos_base = zeros<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">6</span>, <span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
stewart.pos_top = zeros<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">6</span>, <span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
alpha_b = stewart.BP.leg.ang<span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">/</span><span class="org-highlight-numbers-number">180</span>; % angle de décalage par rapport à <span class="org-highlight-numbers-number">120</span> deg (pour positionner les supports bases)
|
|
alpha_t = stewart.TP.leg.ang<span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">/</span><span class="org-highlight-numbers-number">180</span>; % <span class="org-type">+-</span> offset angle from <span class="org-highlight-numbers-number">120</span> degree spacing on top
|
|
|
|
height = <span class="org-rainbow-delimiters-depth-1">(</span>stewart.h<span class="org-type">-</span>stewart.BP.thickness<span class="org-type">-</span>stewart.TP.thickness<span class="org-type">-</span>stewart.Leg.sphere.bottom<span class="org-type">-</span>stewart.Leg.sphere.top<span class="org-type">-</span>stewart.SP.thickness.bottom<span class="org-type">-</span>stewart.SP.thickness.top<span class="org-rainbow-delimiters-depth-1">)</span><span class="org-type">*</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">001</span>; <span class="org-comment">% TODO</span>
|
|
|
|
radius_b = stewart.BP.leg.rad<span class="org-type">*</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">001</span>; <span class="org-comment">% rayon emplacement support base</span>
|
|
radius_t = stewart.TP.leg.rad<span class="org-type">*</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">001</span>; <span class="org-comment">% top radius in meters</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">3</span></span>
|
|
<span class="org-comment">% base points</span>
|
|
angle_m_b = <span class="org-rainbow-delimiters-depth-1">(</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><span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-1">)</span><span class="org-type">*</span> <span class="org-rainbow-delimiters-depth-1">(</span><span class="org-constant">i</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">-</span> alpha_b;
|
|
angle_p_b = <span class="org-rainbow-delimiters-depth-1">(</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><span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-1">)</span><span class="org-type">*</span> <span class="org-rainbow-delimiters-depth-1">(</span><span class="org-constant">i</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">+</span> alpha_b;
|
|
stewart.pos_base<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">2</span><span class="org-type">*</span><span class="org-constant">i</span><span class="org-type">-</span><span class="org-highlight-numbers-number">1</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-1">)</span> = <span class="org-rainbow-delimiters-depth-1">[</span>radius_b<span class="org-type">*</span>cos<span class="org-rainbow-delimiters-depth-2">(</span>angle_m_b<span class="org-rainbow-delimiters-depth-2">)</span>, radius_b<span class="org-type">*</span>sin<span class="org-rainbow-delimiters-depth-2">(</span>angle_m_b<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-rainbow-delimiters-depth-1">]</span>;
|
|
stewart.pos_base<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">2</span><span class="org-type">*</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-1">)</span> = <span class="org-rainbow-delimiters-depth-1">[</span>radius_b<span class="org-type">*</span>cos<span class="org-rainbow-delimiters-depth-2">(</span>angle_p_b<span class="org-rainbow-delimiters-depth-2">)</span>, radius_b<span class="org-type">*</span>sin<span class="org-rainbow-delimiters-depth-2">(</span>angle_p_b<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-rainbow-delimiters-depth-1">]</span>;
|
|
|
|
<span class="org-comment">% top points</span>
|
|
% Top points are <span class="org-highlight-numbers-number">60</span> degrees offset
|
|
angle_m_t = <span class="org-rainbow-delimiters-depth-1">(</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><span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-1">)</span><span class="org-type">*</span> <span class="org-rainbow-delimiters-depth-1">(</span><span class="org-constant">i</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">-</span> alpha_t <span class="org-type">+</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><span class="org-highlight-numbers-number">6</span>;
|
|
angle_p_t = <span class="org-rainbow-delimiters-depth-1">(</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><span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-1">)</span><span class="org-type">*</span> <span class="org-rainbow-delimiters-depth-1">(</span><span class="org-constant">i</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">+</span> alpha_t <span class="org-type">+</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><span class="org-highlight-numbers-number">6</span>;
|
|
stewart.pos_top<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">2</span><span class="org-type">*</span><span class="org-constant">i</span><span class="org-type">-</span><span class="org-highlight-numbers-number">1</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-1">)</span> = <span class="org-rainbow-delimiters-depth-1">[</span>radius_t<span class="org-type">*</span>cos<span class="org-rainbow-delimiters-depth-2">(</span>angle_m_t<span class="org-rainbow-delimiters-depth-2">)</span>, radius_t<span class="org-type">*</span>sin<span class="org-rainbow-delimiters-depth-2">(</span>angle_m_t<span class="org-rainbow-delimiters-depth-2">)</span>, height<span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
stewart.pos_top<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">2</span><span class="org-type">*</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-1">)</span> = <span class="org-rainbow-delimiters-depth-1">[</span>radius_t<span class="org-type">*</span>cos<span class="org-rainbow-delimiters-depth-2">(</span>angle_p_t<span class="org-rainbow-delimiters-depth-2">)</span>, radius_t<span class="org-type">*</span>sin<span class="org-rainbow-delimiters-depth-2">(</span>angle_p_t<span class="org-rainbow-delimiters-depth-2">)</span>, height<span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
<span class="org-keyword">end</span>
|
|
|
|
<span class="org-comment">% permute pos_top points so that legs are end points of base and top points</span>
|
|
stewart.pos_top = <span class="org-rainbow-delimiters-depth-1">[</span>stewart.pos_top<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">6</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span>; stewart.pos_top<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">5</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">]</span>; %<span class="org-highlight-numbers-number">6th</span> point on top connects to <span class="org-highlight-numbers-number">1st</span> on bottom
|
|
stewart.pos_top_tranform = stewart.pos_top <span class="org-type">-</span> height<span class="org-type">*</span><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-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-2">)</span>,ones<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">6</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-matlab-cellbreak"><span class="org-comment">%% leg vectors</span></span>
|
|
legs = stewart.pos_top <span class="org-type">-</span> stewart.pos_base;
|
|
leg_length = 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>;
|
|
leg_vectors = zeros<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">6</span>, <span class="org-highlight-numbers-number">3</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>
|
|
leg_length<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-constant">i</span><span class="org-rainbow-delimiters-depth-1">)</span> = norm<span class="org-rainbow-delimiters-depth-1">(</span>legs<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
leg_vectors<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> = legs<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> leg_length<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-constant">i</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
<span class="org-keyword">end</span>
|
|
|
|
stewart.Leg.lenght = <span class="org-highlight-numbers-number">1000</span><span class="org-type">*</span>leg_length<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><span class="org-highlight-numbers-number">1</span>.<span class="org-highlight-numbers-number">5</span>;
|
|
stewart.Leg.shape.bot = <span class="org-rainbow-delimiters-depth-1">[</span><span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span>; ...
|
|
stewart.Leg.rad.bottom <span class="org-highlight-numbers-number">0</span>; ...
|
|
stewart.Leg.rad.bottom stewart.Leg.lenght; ...
|
|
stewart.Leg.rad.top stewart.Leg.lenght; ...
|
|
stewart.Leg.rad.top <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">2</span><span class="org-type">*</span>stewart.Leg.lenght; ...
|
|
<span class="org-highlight-numbers-number">0</span> <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">2</span><span class="org-type">*</span>stewart.Leg.lenght<span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Calculate revolute and cylindrical axes</span></span>
|
|
rev1 = zeros<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">6</span>, <span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
rev2 = zeros<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">6</span>, <span class="org-highlight-numbers-number">3</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
cyl1 = zeros<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">6</span>, <span class="org-highlight-numbers-number">3</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>
|
|
rev1<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> = cross<span class="org-rainbow-delimiters-depth-1">(</span>leg_vectors<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-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><span class="org-rainbow-delimiters-depth-2">]</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
rev1<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> = rev1<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> norm<span class="org-rainbow-delimiters-depth-1">(</span>rev1<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
rev2<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> cross<span class="org-rainbow-delimiters-depth-1">(</span>rev1<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span>, leg_vectors<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
rev2<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> = rev2<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> norm<span class="org-rainbow-delimiters-depth-1">(</span>rev2<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
cyl1<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> = leg_vectors<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-keyword">end</span>
|
|
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Coordinate systems</span></span>
|
|
stewart.lower_leg = struct<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'rotation'</span>, eye<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-rainbow-delimiters-depth-1">)</span>;
|
|
stewart.upper_leg = struct<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'rotation'</span>, eye<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-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>
|
|
stewart.lower_leg<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-constant">i</span><span class="org-rainbow-delimiters-depth-1">)</span>.rotation = <span class="org-rainbow-delimiters-depth-1">[</span>rev1<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">'</span>, rev2<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">'</span>, cyl1<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">'</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
stewart.upper_leg<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-constant">i</span><span class="org-rainbow-delimiters-depth-1">)</span>.rotation = <span class="org-rainbow-delimiters-depth-1">[</span>rev1<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">'</span>, rev2<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">'</span>, cyl1<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-constant">i</span>,<span class="org-type">:</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">'</span><span class="org-rainbow-delimiters-depth-1">]</span>;
|
|
<span class="org-keyword">end</span>
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Position Matrix</span></span>
|
|
stewart.M_pos_base = stewart.pos_base <span class="org-type">+</span> <span class="org-rainbow-delimiters-depth-1">(</span>height<span class="org-type">+</span><span class="org-rainbow-delimiters-depth-2">(</span>stewart.TP.thickness<span class="org-type">+</span>stewart.Leg.sphere.top<span class="org-type">+</span>stewart.SP.thickness.top<span class="org-type">+</span>stewart.jacobian<span class="org-rainbow-delimiters-depth-2">)</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-rainbow-delimiters-depth-1">)</span><span class="org-type">*</span><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-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-2">)</span>,ones<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">6</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-matlab-cellbreak"><span class="org-comment">%% Compute Jacobian Matrix</span></span>
|
|
aa = stewart.pos_top_tranform <span class="org-type">+</span> <span class="org-rainbow-delimiters-depth-1">(</span>stewart.jacobian <span class="org-type">-</span> stewart.TP.thickness <span class="org-type">-</span> stewart.SP.height.top<span class="org-rainbow-delimiters-depth-1">)</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>zeros<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">6</span>, <span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-2">)</span>,ones<span class="org-rainbow-delimiters-depth-2">(</span><span class="org-highlight-numbers-number">6</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>;
|
|
stewart.J = getJacobianMatrix<span class="org-rainbow-delimiters-depth-1">(</span>leg_vectors<span class="org-type">'</span>, aa<span class="org-type">'</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
<span class="org-keyword">end</span>
|
|
|
|
<span class="org-keyword">function</span> <span class="org-variable-name">J</span> = <span class="org-function-name">getJacobianMatrix</span><span class="org-rainbow-delimiters-depth-1">(</span><span class="org-variable-name">RM</span>,<span class="org-variable-name">M_pos_base</span><span class="org-rainbow-delimiters-depth-1">)</span>
|
|
% RM<span class="org-type">:</span> [<span class="org-highlight-numbers-number">3x6</span>] unit vector of each leg in the fixed frame
|
|
% M_pos_base<span class="org-type">:</span> [<span class="org-highlight-numbers-number">3x6</span>] vector of the leg connection at the top platform location in the fixed frame
|
|
J = zeros<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">6</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
J<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-type">:</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> = RM<span class="org-type">'</span>;
|
|
J<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-type">:</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> = cross<span class="org-rainbow-delimiters-depth-1">(</span>M_pos_base, RM<span class="org-rainbow-delimiters-depth-1">)</span><span class="org-type">'</span>;
|
|
<span class="org-keyword">end</span>
|
|
<span class="org-keyword">end</span>
|
|
</pre>
|
|
</div>
|
|
</div>
|
|
</div>
|
|
|
|
<div id="outline-container-orgde38f10" class="outline-3">
|
|
<h3 id="orgde38f10"><span class="section-number-3">2.10</span> Cedrat Actuator</h3>
|
|
<div class="outline-text-3" id="text-2-10">
|
|
<p>
|
|
<a id="orgbfb8cdb"></a>
|
|
</p>
|
|
|
|
<p>
|
|
This Matlab function is accessible <a href="../src/initializeCedratPiezo.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">cedrat</span><span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">]</span></span> = <span class="org-function-name">initializeCedratPiezo</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">%% Stewart Object</span></span>
|
|
cedrat = struct<span class="org-rainbow-delimiters-depth-1">()</span>;
|
|
cedrat.k = <span class="org-highlight-numbers-number">10e7</span>; <span class="org-comment">% Linear Stiffness of each "blade" [N/m]</span>
|
|
cedrat.ka = <span class="org-highlight-numbers-number">10e7</span>; <span class="org-comment">% Linear Stiffness of the stack [N/m]</span>
|
|
|
|
cedrat.c = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">1</span><span class="org-type">*</span>sqrt<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">1</span><span class="org-type">*</span>cedrat.k<span class="org-rainbow-delimiters-depth-1">)</span>; <span class="org-comment">% [N/(m/s)]</span>
|
|
cedrat.ca = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">1</span><span class="org-type">*</span>sqrt<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-highlight-numbers-number">1</span><span class="org-type">*</span>cedrat.ka<span class="org-rainbow-delimiters-depth-1">)</span>; <span class="org-comment">% [N/(m/s)]</span>
|
|
|
|
cedrat.L = <span class="org-highlight-numbers-number">80</span>; <span class="org-comment">% Total Width of the Actuator[mm]</span>
|
|
cedrat.H = <span class="org-highlight-numbers-number">45</span>; <span class="org-comment">% Total Height of the Actuator [mm]</span>
|
|
cedrat.L2 = sqrt<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-rainbow-delimiters-depth-2">(</span>cedrat.L<span class="org-type">/</span><span class="org-highlight-numbers-number">2</span><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>cedrat.H<span class="org-type">/</span><span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-2">)</span><span class="org-type">^</span><span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-1">)</span>; <span class="org-comment">% Length of the elipsoidal sections [mm]</span>
|
|
cedrat.alpha = <span class="org-highlight-numbers-number">180</span><span class="org-type">/</span><span class="org-constant">pi</span><span class="org-type">*</span>atan2<span class="org-rainbow-delimiters-depth-1">(</span>cedrat.L<span class="org-type">/</span><span class="org-highlight-numbers-number">2</span>, cedrat.H<span class="org-type">/</span><span class="org-highlight-numbers-number">2</span><span class="org-rainbow-delimiters-depth-1">)</span>; <span class="org-comment">% [deg]</span>
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Save</span></span>
|
|
save<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'./mat/stages.mat'</span>, <span class="org-string">'cedrat'</span>, <span class="org-string">'-append'</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
<span class="org-keyword">end</span>
|
|
</pre>
|
|
</div>
|
|
</div>
|
|
</div>
|
|
|
|
<div id="outline-container-org3e33550" class="outline-3">
|
|
<h3 id="org3e33550"><span class="section-number-3">2.11</span> Sample</h3>
|
|
<div class="outline-text-3" id="text-2-11">
|
|
<p>
|
|
<a id="org1faaee4"></a>
|
|
</p>
|
|
|
|
<p>
|
|
This Matlab function is accessible <a href="../src/initializeSample.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">sample</span><span class="org-variable-name"><span class="org-rainbow-delimiters-depth-1">]</span></span> = <span class="org-function-name">initializeSample</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>
|
|
sample = struct<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'radius'</span>, <span class="org-highlight-numbers-number">100</span>, ...
|
|
<span class="org-string">'height'</span>, <span class="org-highlight-numbers-number">300</span>, ...
|
|
<span class="org-string">'mass'</span>, <span class="org-highlight-numbers-number">50</span>, ...
|
|
<span class="org-string">'offset'</span>, <span class="org-highlight-numbers-number">0</span>, ...
|
|
<span class="org-string">'color'</span>, <span class="org-rainbow-delimiters-depth-2">[</span><span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">45</span>, <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">45</span>, <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">45</span><span class="org-rainbow-delimiters-depth-2">]</span> ...
|
|
<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>
|
|
sample.<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">%%</span></span>
|
|
sample.k.x = <span class="org-highlight-numbers-number">1e8</span>;
|
|
sample.c.x = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">1</span><span class="org-type">*</span>sqrt<span class="org-rainbow-delimiters-depth-1">(</span>sample.k.x<span class="org-type">*</span>sample.mass<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
sample.k.y = <span class="org-highlight-numbers-number">1e8</span>;
|
|
sample.c.y = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">1</span><span class="org-type">*</span>sqrt<span class="org-rainbow-delimiters-depth-1">(</span>sample.k.y<span class="org-type">*</span>sample.mass<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
sample.k.z = <span class="org-highlight-numbers-number">1e8</span>;
|
|
sample.c.z = <span class="org-highlight-numbers-number">0</span>.<span class="org-highlight-numbers-number">1</span><span class="org-type">*</span>sqrt<span class="org-rainbow-delimiters-depth-1">(</span>sample.k.z<span class="org-type">*</span>sample.mass<span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
|
|
<span class="org-matlab-cellbreak"><span class="org-comment">%% Save</span></span>
|
|
save<span class="org-rainbow-delimiters-depth-1">(</span><span class="org-string">'./mat/stages.mat'</span>, <span class="org-string">'sample'</span>, <span class="org-string">'-append'</span><span class="org-rainbow-delimiters-depth-1">)</span>;
|
|
<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. 16:56</p>
|
|
<p class="validation"><a href="http://validator.w3.org/check?uri=referer">Validate</a></p>
|
|
</div>
|
|
</body>
|
|
</html>
|