Remove useless parameters and add some comments

This commit is contained in:
Thomas Dehaeze 2018-06-06 18:39:38 +02:00
parent 8310c58a64
commit 2872f048d6
2 changed files with 57 additions and 41 deletions

Binary file not shown.

78
Data.m
View File

@ -7,76 +7,93 @@ Ts = 1e-4; % Sampling time [s]
Tsim = 1; % Simulation time [s]
%% Gravity
g = 0 ; % [m/s^2]
g = 0 ; % Gravity along the z axis [m/s^2]
%% Granite
granite = struct();
granite.m = smiData.Solid(5).mass;
granite.k.ax = 1e10; % x-y-z Stiffness of the granite [N/m]
granite.ksi.ax = 10;
granite = updateDamping(granite);
%% Translation stage
ty = struct();
ty.m = smiData.Solid(4).mass+smiData.Solid(6).mass+smiData.Solid(7).mass+smiData.Solid(8).mass+smiData.Solid(9).mass+4*smiData.Solid(11).mass+smiData.Solid(24).mass+smiData.Solid(25).mass+smiData.Solid(28).mass;
ty.k.ax = 1e7/4; %z
ty.k.rad = 9e9/4; %x
ty.k.rrad = 9e9/4; %y
ty.k.ax = 1e7/4; % Axial Stiffness for each of the 4 guidance (y) [N/m]
ty.k.rad = 9e9/4; % Radial Stiffness for each of the 4 guidance (x-z) [N/m]
ty.ksi.ax = 10;
ty.ksi.rad = 10;
ty.ksi.rrad = 10;
ty = updateDamping(ty);
%% Tilt
%% Tilt Stage
ry = struct();
ry.m = smiData.Solid(26).mass+smiData.Solid(18).mass+smiData.Solid(10).mass;
ry.k.h = 357e6/4; %y
ry.k.rad = 555e6/4; %x
ry.k.rrad = 238e6/4; %z
ry.k.tilt = 1e4 ; % rz in actuator
ry.k.h = 357e6/4; % Stiffness in the direction of the guidance [N/m]
ry.k.rad = 555e6/4; % Stiffness in the top direction [N/m]
ry.k.rrad = 238e6/4; % Stiffness in the side direction [N/m]
ry.k.tilt = 1e4 ; % Rotation stiffness around y [N*m/deg]
ry.ksi.h = 10;
ry.ksi.rad = 10;
ry.ksi.rrad = 10;
ry.ksi.tilt = 10;
ry = updateDamping(ry);
%% Spindle
rz = struct();
rz.m = smiData.Solid(12).mass+6*smiData.Solid(20).mass+smiData.Solid(19).mass;
rz.k.ax = 2e9; %x
rz.k.rad = 7e8; %z
rz.k.rrad = 7e8; %y
rz.k.tilt = 1e5;
rz.k.rot = 1e5;
rz.k.ax = 2e9; % Axial Stiffness [N/m]
rz.k.rad = 7e8; % Radial Stiffness [N/m]
rz.k.tilt = 1e5; % TODO
rz.k.rot = 1e5; % TODO
rz.ksi.ax = 10;
rz.ksi.rad = 10;
rz.ksi.rrad = 10;
rz.ksi.tilt = 1;
rz.ksi.rot = 1;
rz = updateDamping(rz);
%% Hexapod Symétrie
% TODO - is now defined by the stewart-simscape project
hexapod = struct();
hexapod.m = smiData.Solid(16).mass;
hexapod.k.ax = (138e6/6)*1.2; %z
hexapod.k.ax = (138e6/6)*1.2; % Leg stiffness [N/m]
hexapod.ksi.ax = 10;
hexapod = updateDamping(hexapod);
%% Axis Corrector
%% Center of gravity compensation
axisc = struct();
axisc.m = smiData.Solid(30).mass;
axisc.k.ax = 1; % (N*m/deg))
axisc.k.ax = 1; % TODO [N*m/deg)]
axisc.ksi.ax = 1;
axisc = updateDamping(axisc);
%% NASS
% TODO - is now defined by the stewart-simscape project
nass = struct();
nass.m = smiData.Solid(27).mass;
nass.k.ax = 5e7; %z
nass.ksi.ax = 10;
nass = updateDamping(nass);
%% Wobble
wob = struct();
wob.m = smiData.Solid(5).mass;
wob.k.ax = 1e10;
wob.ksi.ax = 10;
wob = updateDamping(wob);
nass.m = smiData.Solid(27).mass;
nass.k.ax = 5e7; % Leg stiffness [N/m]
nass.ksi.ax = 10;
nass = updateDamping(nass);
%%
function element = updateDamping(element)
@ -85,4 +102,3 @@ function element = updateDamping(element)
element.c.(field{i}) = 1/element.ksi.(field{i})*sqrt(element.k.(field{i})/element.m);
end
end