diff --git a/matlab/src/computeJacobian.m b/matlab/src/computeJacobian.m
new file mode 100644
index 0000000..3c4acfb
--- /dev/null
+++ b/matlab/src/computeJacobian.m
@@ -0,0 +1,35 @@
+ function [stewart] = computeJacobian(stewart)
+ % computeJacobian -
+ %
+ % Syntax: [stewart] = computeJacobian(stewart)
+ %
+ % Inputs:
+ % - stewart - With at least the following fields:
+ % - geometry.As [3x6] - The 6 unit vectors for each strut expressed in {A}
+ % - geometry.Ab [3x6] - The 6 position of the joints bi expressed in {A}
+ % - actuators.K [6x1] - Total stiffness of the actuators
+ %
+ % Outputs:
+ % - stewart - With the 3 added field:
+ % - kinematics.J [6x6] - The Jacobian Matrix
+ % - kinematics.K [6x6] - The Stiffness Matrix
+ % - kinematics.C [6x6] - The Compliance Matrix
+
+ assert(isfield(stewart.geometry, 'As'), 'stewart.geometry should have attribute As')
+ As = stewart.geometry.As;
+
+ assert(isfield(stewart.geometry, 'Ab'), 'stewart.geometry should have attribute Ab')
+ Ab = stewart.geometry.Ab;
+
+ assert(isfield(stewart.actuators, 'K'), 'stewart.actuators should have attribute K')
+ Ki = stewart.actuators.K;
+
+ J = [As' , cross(Ab, As)'];
+
+ K = J'*diag(Ki)*J;
+
+ C = inv(K);
+
+ stewart.kinematics.J = J;
+ stewart.kinematics.K = K;
+ stewart.kinematics.C = C;
diff --git a/matlab/src/computeJointsPose.m b/matlab/src/computeJointsPose.m
new file mode 100644
index 0000000..7f93655
--- /dev/null
+++ b/matlab/src/computeJointsPose.m
@@ -0,0 +1,78 @@
+ function [stewart] = computeJointsPose(stewart)
+ % computeJointsPose -
+ %
+ % Syntax: [stewart] = computeJointsPose(stewart)
+ %
+ % Inputs:
+ % - stewart - A structure with the following fields
+ % - platform_F.Fa [3x6] - Its i'th column is the position vector of joint ai with respect to {F}
+ % - platform_M.Mb [3x6] - Its i'th column is the position vector of joint bi with respect to {M}
+ % - platform_F.FO_A [3x1] - Position of {A} with respect to {F}
+ % - platform_M.MO_B [3x1] - Position of {B} with respect to {M}
+ % - geometry.FO_M [3x1] - Position of {M} with respect to {F}
+ %
+ % Outputs:
+ % - stewart - A structure with the following added fields
+ % - geometry.Aa [3x6] - The i'th column is the position of ai with respect to {A}
+ % - geometry.Ab [3x6] - The i'th column is the position of bi with respect to {A}
+ % - geometry.Ba [3x6] - The i'th column is the position of ai with respect to {B}
+ % - geometry.Bb [3x6] - The i'th column is the position of bi with respect to {B}
+ % - geometry.l [6x1] - The i'th element is the initial length of strut i
+ % - geometry.As [3x6] - The i'th column is the unit vector of strut i expressed in {A}
+ % - geometry.Bs [3x6] - The i'th column is the unit vector of strut i expressed in {B}
+ % - struts_F.l [6x1] - Length of the Fixed part of the i'th strut
+ % - struts_M.l [6x1] - Length of the Mobile part of the i'th strut
+ % - platform_F.FRa [3x3x6] - The i'th 3x3 array is the rotation matrix to orientate the bottom of the i'th strut from {F}
+ % - platform_M.MRb [3x3x6] - The i'th 3x3 array is the rotation matrix to orientate the top of the i'th strut from {M}
+
+ assert(isfield(stewart.platform_F, 'Fa'), 'stewart.platform_F should have attribute Fa')
+ Fa = stewart.platform_F.Fa;
+
+ assert(isfield(stewart.platform_M, 'Mb'), 'stewart.platform_M should have attribute Mb')
+ Mb = stewart.platform_M.Mb;
+
+ assert(isfield(stewart.platform_F, 'FO_A'), 'stewart.platform_F should have attribute FO_A')
+ FO_A = stewart.platform_F.FO_A;
+
+ assert(isfield(stewart.platform_M, 'MO_B'), 'stewart.platform_M should have attribute MO_B')
+ MO_B = stewart.platform_M.MO_B;
+
+ assert(isfield(stewart.geometry, 'FO_M'), 'stewart.geometry should have attribute FO_M')
+ FO_M = stewart.geometry.FO_M;
+
+ Aa = Fa - repmat(FO_A, [1, 6]);
+ Bb = Mb - repmat(MO_B, [1, 6]);
+
+ Ab = Bb - repmat(-MO_B-FO_M+FO_A, [1, 6]);
+ Ba = Aa - repmat( MO_B+FO_M-FO_A, [1, 6]);
+
+ As = (Ab - Aa)./vecnorm(Ab - Aa); % As_i is the i'th vector of As
+
+ l = vecnorm(Ab - Aa)';
+
+ Bs = (Bb - Ba)./vecnorm(Bb - Ba);
+
+ FRa = zeros(3,3,6);
+ MRb = zeros(3,3,6);
+
+ for i = 1:6
+ FRa(:,:,i) = [cross([0;1;0], As(:,i)) , cross(As(:,i), cross([0;1;0], As(:,i))) , As(:,i)];
+ FRa(:,:,i) = FRa(:,:,i)./vecnorm(FRa(:,:,i));
+
+ MRb(:,:,i) = [cross([0;1;0], Bs(:,i)) , cross(Bs(:,i), cross([0;1;0], Bs(:,i))) , Bs(:,i)];
+ MRb(:,:,i) = MRb(:,:,i)./vecnorm(MRb(:,:,i));
+ end
+
+ stewart.geometry.Aa = Aa;
+ stewart.geometry.Ab = Ab;
+ stewart.geometry.Ba = Ba;
+ stewart.geometry.Bb = Bb;
+ stewart.geometry.As = As;
+ stewart.geometry.Bs = Bs;
+ stewart.geometry.l = l;
+
+ stewart.struts_F.l = l/2;
+ stewart.struts_M.l = l/2;
+
+ stewart.platform_F.FRa = FRa;
+ stewart.platform_M.MRb = MRb;
diff --git a/matlab/src/generateGeneralConfiguration.m b/matlab/src/generateGeneralConfiguration.m
new file mode 100644
index 0000000..8964ccc
--- /dev/null
+++ b/matlab/src/generateGeneralConfiguration.m
@@ -0,0 +1,39 @@
+ function [stewart] = generateGeneralConfiguration(stewart, args)
+ % generateGeneralConfiguration - Generate a Very General Configuration
+ %
+ % Syntax: [stewart] = generateGeneralConfiguration(stewart, args)
+ %
+ % Inputs:
+ % - args - Can have the following fields:
+ % - FH [1x1] - Height of the position of the fixed joints with respect to the frame {F} [m]
+ % - FR [1x1] - Radius of the position of the fixed joints in the X-Y [m]
+ % - FTh [6x1] - Angles of the fixed joints in the X-Y plane with respect to the X axis [rad]
+ % - MH [1x1] - Height of the position of the mobile joints with respect to the frame {M} [m]
+ % - FR [1x1] - Radius of the position of the mobile joints in the X-Y [m]
+ % - MTh [6x1] - Angles of the mobile joints in the X-Y plane with respect to the X axis [rad]
+ %
+ % Outputs:
+ % - stewart - updated Stewart structure with the added fields:
+ % - platform_F.Fa [3x6] - Its i'th column is the position vector of joint ai with respect to {F}
+ % - platform_M.Mb [3x6] - Its i'th column is the position vector of joint bi with respect to {M}
+
+ arguments
+ stewart
+ args.FH (1,1) double {mustBeNumeric, mustBePositive} = 15e-3
+ args.FR (1,1) double {mustBeNumeric, mustBePositive} = 115e-3;
+ args.FTh (6,1) double {mustBeNumeric} = [-10, 10, 120-10, 120+10, 240-10, 240+10]*(pi/180);
+ args.MH (1,1) double {mustBeNumeric, mustBePositive} = 15e-3
+ args.MR (1,1) double {mustBeNumeric, mustBePositive} = 90e-3;
+ args.MTh (6,1) double {mustBeNumeric} = [-60+10, 60-10, 60+10, 180-10, 180+10, -60-10]*(pi/180);
+ end
+
+ Fa = zeros(3,6);
+ Mb = zeros(3,6);
+
+ for i = 1:6
+ Fa(:,i) = [args.FR*cos(args.FTh(i)); args.FR*sin(args.FTh(i)); args.FH];
+ Mb(:,i) = [args.MR*cos(args.MTh(i)); args.MR*sin(args.MTh(i)); -args.MH];
+ end
+
+ stewart.platform_F.Fa = Fa;
+ stewart.platform_M.Mb = Mb;
diff --git a/matlab/src/initializeCylindricalPlatforms.m b/matlab/src/initializeCylindricalPlatforms.m
new file mode 100644
index 0000000..f8e6103
--- /dev/null
+++ b/matlab/src/initializeCylindricalPlatforms.m
@@ -0,0 +1,59 @@
+ function [stewart] = initializeCylindricalPlatforms(stewart, args)
+ % initializeCylindricalPlatforms - Initialize the geometry of the Fixed and Mobile Platforms
+ %
+ % Syntax: [stewart] = initializeCylindricalPlatforms(args)
+ %
+ % Inputs:
+ % - args - Structure with the following fields:
+ % - Fpm [1x1] - Fixed Platform Mass [kg]
+ % - Fph [1x1] - Fixed Platform Height [m]
+ % - Fpr [1x1] - Fixed Platform Radius [m]
+ % - Mpm [1x1] - Mobile Platform Mass [kg]
+ % - Mph [1x1] - Mobile Platform Height [m]
+ % - Mpr [1x1] - Mobile Platform Radius [m]
+ %
+ % Outputs:
+ % - stewart - updated Stewart structure with the added fields:
+ % - platform_F [struct] - structure with the following fields:
+ % - type = 1
+ % - M [1x1] - Fixed Platform Mass [kg]
+ % - I [3x3] - Fixed Platform Inertia matrix [kg*m^2]
+ % - H [1x1] - Fixed Platform Height [m]
+ % - R [1x1] - Fixed Platform Radius [m]
+ % - platform_M [struct] - structure with the following fields:
+ % - M [1x1] - Mobile Platform Mass [kg]
+ % - I [3x3] - Mobile Platform Inertia matrix [kg*m^2]
+ % - H [1x1] - Mobile Platform Height [m]
+ % - R [1x1] - Mobile Platform Radius [m]
+
+ arguments
+ stewart
+ args.Fpm (1,1) double {mustBeNumeric, mustBePositive} = 1
+ args.Fph (1,1) double {mustBeNumeric, mustBePositive} = 10e-3
+ args.Fpr (1,1) double {mustBeNumeric, mustBePositive} = 125e-3
+ args.Mpm (1,1) double {mustBeNumeric, mustBePositive} = 1
+ args.Mph (1,1) double {mustBeNumeric, mustBePositive} = 10e-3
+ args.Mpr (1,1) double {mustBeNumeric, mustBePositive} = 100e-3
+ end
+
+ I_F = diag([1/12*args.Fpm * (3*args.Fpr^2 + args.Fph^2), ...
+ 1/12*args.Fpm * (3*args.Fpr^2 + args.Fph^2), ...
+ 1/2 *args.Fpm * args.Fpr^2]);
+
+ I_M = diag([1/12*args.Mpm * (3*args.Mpr^2 + args.Mph^2), ...
+ 1/12*args.Mpm * (3*args.Mpr^2 + args.Mph^2), ...
+ 1/2 *args.Mpm * args.Mpr^2]);
+
+ stewart.platform_F.type = 1;
+
+ stewart.platform_F.I = I_F;
+ stewart.platform_F.M = args.Fpm;
+ stewart.platform_F.R = args.Fpr;
+ stewart.platform_F.H = args.Fph;
+
+ stewart.platform_M.type = 1;
+
+ stewart.platform_M.I = I_M;
+ stewart.platform_M.M = args.Mpm;
+ stewart.platform_M.R = args.Mpr;
+ stewart.platform_M.H = args.Mph;
diff --git a/matlab/src/initializeCylindricalStruts.m b/matlab/src/initializeCylindricalStruts.m
new file mode 100644
index 0000000..5af925e
--- /dev/null
+++ b/matlab/src/initializeCylindricalStruts.m
@@ -0,0 +1,71 @@
+ function [stewart] = initializeCylindricalStruts(stewart, args)
+ % initializeCylindricalStruts - Define the mass and moment of inertia of cylindrical struts
+ %
+ % Syntax: [stewart] = initializeCylindricalStruts(args)
+ %
+ % Inputs:
+ % - args - Structure with the following fields:
+ % - Fsm [1x1] - Mass of the Fixed part of the struts [kg]
+ % - Fsh [1x1] - Height of cylinder for the Fixed part of the struts [m]
+ % - Fsr [1x1] - Radius of cylinder for the Fixed part of the struts [m]
+ % - Msm [1x1] - Mass of the Mobile part of the struts [kg]
+ % - Msh [1x1] - Height of cylinder for the Mobile part of the struts [m]
+ % - Msr [1x1] - Radius of cylinder for the Mobile part of the struts [m]
+ %
+ % Outputs:
+ % - stewart - updated Stewart structure with the added fields:
+ % - struts_F [struct] - structure with the following fields:
+ % - M [6x1] - Mass of the Fixed part of the struts [kg]
+ % - I [3x3x6] - Moment of Inertia for the Fixed part of the struts [kg*m^2]
+ % - H [6x1] - Height of cylinder for the Fixed part of the struts [m]
+ % - R [6x1] - Radius of cylinder for the Fixed part of the struts [m]
+ % - struts_M [struct] - structure with the following fields:
+ % - M [6x1] - Mass of the Mobile part of the struts [kg]
+ % - I [3x3x6] - Moment of Inertia for the Mobile part of the struts [kg*m^2]
+ % - H [6x1] - Height of cylinder for the Mobile part of the struts [m]
+ % - R [6x1] - Radius of cylinder for the Mobile part of the struts [m]
+
+ arguments
+ stewart
+ args.Fsm (1,1) double {mustBeNumeric, mustBePositive} = 0.1
+ args.Fsh (1,1) double {mustBeNumeric, mustBePositive} = 50e-3
+ args.Fsr (1,1) double {mustBeNumeric, mustBePositive} = 5e-3
+ args.Msm (1,1) double {mustBeNumeric, mustBePositive} = 0.1
+ args.Msh (1,1) double {mustBeNumeric, mustBePositive} = 50e-3
+ args.Msr (1,1) double {mustBeNumeric, mustBePositive} = 5e-3
+ end
+
+ Fsm = ones(6,1).*args.Fsm;
+ Fsh = ones(6,1).*args.Fsh;
+ Fsr = ones(6,1).*args.Fsr;
+
+ Msm = ones(6,1).*args.Msm;
+ Msh = ones(6,1).*args.Msh;
+ Msr = ones(6,1).*args.Msr;
+
+ I_F = zeros(3, 3, 6); % Inertia of the "fixed" part of the strut
+ I_M = zeros(3, 3, 6); % Inertia of the "mobile" part of the strut
+
+ for i = 1:6
+ I_F(:,:,i) = diag([1/12 * Fsm(i) * (3*Fsr(i)^2 + Fsh(i)^2), ...
+ 1/12 * Fsm(i) * (3*Fsr(i)^2 + Fsh(i)^2), ...
+ 1/2 * Fsm(i) * Fsr(i)^2]);
+
+ I_M(:,:,i) = diag([1/12 * Msm(i) * (3*Msr(i)^2 + Msh(i)^2), ...
+ 1/12 * Msm(i) * (3*Msr(i)^2 + Msh(i)^2), ...
+ 1/2 * Msm(i) * Msr(i)^2]);
+ end
+
+ stewart.struts_M.type = 1;
+
+ stewart.struts_M.I = I_M;
+ stewart.struts_M.M = Msm;
+ stewart.struts_M.R = Msr;
+ stewart.struts_M.H = Msh;
+
+ stewart.struts_F.type = 1;
+
+ stewart.struts_F.I = I_F;
+ stewart.struts_F.M = Fsm;
+ stewart.struts_F.R = Fsr;
+ stewart.struts_F.H = Fsh;
diff --git a/matlab/src/initializeDisturbances.m b/matlab/src/initializeDisturbances.m
index 8c1a881..d7b8214 100644
--- a/matlab/src/initializeDisturbances.m
+++ b/matlab/src/initializeDisturbances.m
@@ -23,7 +23,7 @@
args.Frz_z logical {mustBeNumericOrLogical} = true
end
- load('./mat/dist_psd.mat', 'dist_f');
+ load('dist_psd.mat', 'dist_f');
dist_f.f = dist_f.f(2:end);
dist_f.psd_gm = dist_f.psd_gm(2:end);
@@ -132,7 +132,6 @@
Fty_z = Fty_z - Fty_z(1);
Frz_z = Frz_z - Frz_z(1);
-micro_hexapod = stewart;
if exist('./mat', 'dir')
if exist('./mat/nass_disturbances.mat', 'file')
save('mat/nass_disturbances.mat', 'Dwx', 'Dwy', 'Dwz', 'Fty_x', 'Fty_z', 'Frz_z', 'Fd', 'Ts', 't', 'args', '-append');
diff --git a/matlab/src/initializeFramesPositions.m b/matlab/src/initializeFramesPositions.m
new file mode 100644
index 0000000..6a76e4b
--- /dev/null
+++ b/matlab/src/initializeFramesPositions.m
@@ -0,0 +1,35 @@
+ function [stewart] = initializeFramesPositions(stewart, args)
+ % initializeFramesPositions - Initialize the positions of frames {A}, {B}, {F} and {M}
+ %
+ % Syntax: [stewart] = initializeFramesPositions(stewart, args)
+ %
+ % Inputs:
+ % - args - Can have the following fields:
+ % - H [1x1] - Total Height of the Stewart Platform (height from {F} to {M}) [m]
+ % - MO_B [1x1] - Height of the frame {B} with respect to {M} [m]
+ %
+ % Outputs:
+ % - stewart - A structure with the following fields:
+ % - geometry.H [1x1] - Total Height of the Stewart Platform [m]
+ % - geometry.FO_M [3x1] - Position of {M} with respect to {F} [m]
+ % - platform_M.MO_B [3x1] - Position of {B} with respect to {M} [m]
+ % - platform_F.FO_A [3x1] - Position of {A} with respect to {F} [m]
+
+ arguments
+ stewart
+ args.H (1,1) double {mustBeNumeric, mustBePositive} = 90e-3
+ args.MO_B (1,1) double {mustBeNumeric} = 50e-3
+ end
+
+ H = args.H; % Total Height of the Stewart Platform [m]
+
+ FO_M = [0; 0; H]; % Position of {M} with respect to {F} [m]
+
+ MO_B = [0; 0; args.MO_B]; % Position of {B} with respect to {M} [m]
+
+ FO_A = MO_B + FO_M; % Position of {A} with respect to {F} [m]
+
+ stewart.geometry.H = H;
+ stewart.geometry.FO_M = FO_M;
+ stewart.platform_M.MO_B = MO_B;
+ stewart.platform_F.FO_A = FO_A;
diff --git a/matlab/src/initializeInertialSensor.m b/matlab/src/initializeInertialSensor.m
new file mode 100644
index 0000000..e64653f
--- /dev/null
+++ b/matlab/src/initializeInertialSensor.m
@@ -0,0 +1,48 @@
+ function [stewart] = initializeInertialSensor(stewart, args)
+ % initializeInertialSensor - Initialize the inertial sensor in each strut
+ %
+ % Syntax: [stewart] = initializeInertialSensor(args)
+ %
+ % Inputs:
+ % - args - Structure with the following fields:
+ % - type - 'geophone', 'accelerometer', 'none'
+ % - mass [1x1] - Weight of the inertial mass [kg]
+ % - freq [1x1] - Cutoff frequency [Hz]
+ %
+ % Outputs:
+ % - stewart - updated Stewart structure with the added fields:
+ % - stewart.sensors.inertial
+ % - type - 1 (geophone), 2 (accelerometer), 3 (none)
+ % - K [1x1] - Stiffness [N/m]
+ % - C [1x1] - Damping [N/(m/s)]
+ % - M [1x1] - Inertial Mass [kg]
+ % - G [1x1] - Gain
+
+ arguments
+ stewart
+ args.type char {mustBeMember(args.type,{'geophone', 'accelerometer', 'none'})} = 'none'
+ args.mass (1,1) double {mustBeNumeric, mustBeNonnegative} = 1e-2
+ args.freq (1,1) double {mustBeNumeric, mustBeNonnegative} = 1e3
+ end
+
+ sensor = struct();
+
+ switch args.type
+ case 'geophone'
+ sensor.type = 1;
+
+ sensor.M = args.mass;
+ sensor.K = sensor.M * (2*pi*args.freq)^2;
+ sensor.C = 2*sqrt(sensor.M * sensor.K);
+ case 'accelerometer'
+ sensor.type = 2;
+
+ sensor.M = args.mass;
+ sensor.K = sensor.M * (2*pi*args.freq)^2;
+ sensor.C = 2*sqrt(sensor.M * sensor.K);
+ sensor.G = -sensor.K/sensor.M;
+ case 'none'
+ sensor.type = 3;
+ end
+
+ stewart.sensors.inertial = sensor;
diff --git a/matlab/src/initializeJointDynamics.m b/matlab/src/initializeJointDynamics.m
new file mode 100644
index 0000000..2596f6e
--- /dev/null
+++ b/matlab/src/initializeJointDynamics.m
@@ -0,0 +1,131 @@
+ function [stewart] = initializeJointDynamics(stewart, args)
+ % initializeJointDynamics - Add Stiffness and Damping properties for the spherical joints
+ %
+ % Syntax: [stewart] = initializeJointDynamics(args)
+ %
+ % Inputs:
+ % - args - Structure with the following fields:
+ % - type_F - 'universal', 'spherical', 'universal_p', 'spherical_p'
+ % - type_M - 'universal', 'spherical', 'universal_p', 'spherical_p'
+ % - Kf_M [6x1] - Bending (Rx, Ry) Stiffness for each top joints [(N.m)/rad]
+ % - Kt_M [6x1] - Torsion (Rz) Stiffness for each top joints [(N.m)/rad]
+ % - Cf_M [6x1] - Bending (Rx, Ry) Damping of each top joint [(N.m)/(rad/s)]
+ % - Ct_M [6x1] - Torsion (Rz) Damping of each top joint [(N.m)/(rad/s)]
+ % - Kf_F [6x1] - Bending (Rx, Ry) Stiffness for each bottom joints [(N.m)/rad]
+ % - Kt_F [6x1] - Torsion (Rz) Stiffness for each bottom joints [(N.m)/rad]
+ % - Cf_F [6x1] - Bending (Rx, Ry) Damping of each bottom joint [(N.m)/(rad/s)]
+ % - Cf_F [6x1] - Torsion (Rz) Damping of each bottom joint [(N.m)/(rad/s)]
+ %
+ % Outputs:
+ % - stewart - updated Stewart structure with the added fields:
+ % - stewart.joints_F and stewart.joints_M:
+ % - type - 1 (universal), 2 (spherical), 3 (universal perfect), 4 (spherical perfect)
+ % - Kx, Ky, Kz [6x1] - Translation (Tx, Ty, Tz) Stiffness [N/m]
+ % - Kf [6x1] - Flexion (Rx, Ry) Stiffness [(N.m)/rad]
+ % - Kt [6x1] - Torsion (Rz) Stiffness [(N.m)/rad]
+ % - Cx, Cy, Cz [6x1] - Translation (Rx, Ry) Damping [N/(m/s)]
+ % - Cf [6x1] - Flexion (Rx, Ry) Damping [(N.m)/(rad/s)]
+ % - Cb [6x1] - Torsion (Rz) Damping [(N.m)/(rad/s)]
+
+ arguments
+ stewart
+ args.type_F char {mustBeMember(args.type_F,{'universal', 'spherical', 'universal_p', 'spherical_p', 'universal_3dof', 'spherical_3dof', 'flexible'})} = 'universal'
+ args.type_M char {mustBeMember(args.type_M,{'universal', 'spherical', 'universal_p', 'spherical_p', 'universal_3dof', 'spherical_3dof', 'flexible'})} = 'spherical'
+ args.Kf_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 33*ones(6,1)
+ args.Cf_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-4*ones(6,1)
+ args.Kt_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 236*ones(6,1)
+ args.Ct_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-3*ones(6,1)
+ args.Kf_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 33*ones(6,1)
+ args.Cf_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-4*ones(6,1)
+ args.Kt_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 236*ones(6,1)
+ args.Ct_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-3*ones(6,1)
+ args.Ka_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1.2e8*ones(6,1)
+ args.Ca_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e1*ones(6,1)
+ args.Kr_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1.1e7*ones(6,1)
+ args.Cr_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e1*ones(6,1)
+ args.Ka_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1.2e8*ones(6,1)
+ args.Ca_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e1*ones(6,1)
+ args.Kr_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1.1e7*ones(6,1)
+ args.Cr_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e1*ones(6,1)
+ args.K_M double {mustBeNumeric} = zeros(6,6)
+ args.M_M double {mustBeNumeric} = zeros(6,6)
+ args.n_xyz_M double {mustBeNumeric} = zeros(2,3)
+ args.xi_M double {mustBeNumeric} = 0.1
+ args.step_file_M char {} = ''
+ args.K_F double {mustBeNumeric} = zeros(6,6)
+ args.M_F double {mustBeNumeric} = zeros(6,6)
+ args.n_xyz_F double {mustBeNumeric} = zeros(2,3)
+ args.xi_F double {mustBeNumeric} = 0.1
+ args.step_file_F char {} = ''
+ end
+
+ switch args.type_F
+ case 'universal'
+ stewart.joints_F.type = 1;
+ case 'spherical'
+ stewart.joints_F.type = 2;
+ case 'universal_p'
+ stewart.joints_F.type = 3;
+ case 'spherical_p'
+ stewart.joints_F.type = 4;
+ case 'flexible'
+ stewart.joints_F.type = 5;
+ case 'universal_3dof'
+ stewart.joints_F.type = 6;
+ case 'spherical_3dof'
+ stewart.joints_F.type = 7;
+ end
+
+ switch args.type_M
+ case 'universal'
+ stewart.joints_M.type = 1;
+ case 'spherical'
+ stewart.joints_M.type = 2;
+ case 'universal_p'
+ stewart.joints_M.type = 3;
+ case 'spherical_p'
+ stewart.joints_M.type = 4;
+ case 'flexible'
+ stewart.joints_M.type = 5;
+ case 'universal_3dof'
+ stewart.joints_M.type = 6;
+ case 'spherical_3dof'
+ stewart.joints_M.type = 7;
+ end
+
+ stewart.joints_M.Ka = args.Ka_M;
+ stewart.joints_M.Kr = args.Kr_M;
+
+ stewart.joints_F.Ka = args.Ka_F;
+ stewart.joints_F.Kr = args.Kr_F;
+
+ stewart.joints_M.Ca = args.Ca_M;
+ stewart.joints_M.Cr = args.Cr_M;
+
+ stewart.joints_F.Ca = args.Ca_F;
+ stewart.joints_F.Cr = args.Cr_F;
+
+ stewart.joints_M.Kf = args.Kf_M;
+ stewart.joints_M.Kt = args.Kt_M;
+
+ stewart.joints_F.Kf = args.Kf_F;
+ stewart.joints_F.Kt = args.Kt_F;
+
+ stewart.joints_M.Cf = args.Cf_M;
+ stewart.joints_M.Ct = args.Ct_M;
+
+ stewart.joints_F.Cf = args.Cf_F;
+ stewart.joints_F.Ct = args.Ct_F;
+
+ stewart.joints_F.M = args.M_F;
+ stewart.joints_F.K = args.K_F;
+ stewart.joints_F.n_xyz = args.n_xyz_F;
+ stewart.joints_F.xi = args.xi_F;
+ stewart.joints_F.xi = args.xi_F;
+ stewart.joints_F.step_file = args.step_file_F;
+
+ stewart.joints_M.M = args.M_M;
+ stewart.joints_M.K = args.K_M;
+ stewart.joints_M.n_xyz = args.n_xyz_M;
+ stewart.joints_M.xi = args.xi_M;
+ stewart.joints_M.step_file = args.step_file_M;
diff --git a/matlab/src/initializeReferences.m b/matlab/src/initializeReferences.m
index c04196b..df9f3ef 100644
--- a/matlab/src/initializeReferences.m
+++ b/matlab/src/initializeReferences.m
@@ -184,58 +184,16 @@
Dh = struct('time', t, 'signals', struct('values', Dh));
Dhl = struct('time', t, 'signals', struct('values', Dhl));
- %% Axis Compensation - Rm
- t = [0, Ts];
-
- Rm = [args.Rm_pos, args.Rm_pos];
- Rm = struct('time', t, 'signals', struct('values', Rm));
-
- %% Nano-Hexapod
- t = [0, Ts];
- Dn = zeros(length(t), 6);
-
- switch args.Dn_type
- case 'constant'
- Dn = [args.Dn_pos, args.Dn_pos];
-
- load('nass_stages.mat', 'nano_hexapod');
-
- AP = [args.Dn_pos(1) ; args.Dn_pos(2) ; args.Dn_pos(3)];
-
- tx = args.Dn_pos(4);
- ty = args.Dn_pos(5);
- tz = args.Dn_pos(6);
-
- ARB = [cos(tz) -sin(tz) 0;
- sin(tz) cos(tz) 0;
- 0 0 1]*...
- [ cos(ty) 0 sin(ty);
- 0 1 0;
- -sin(ty) 0 cos(ty)]*...
- [1 0 0;
- 0 cos(tx) -sin(tx);
- 0 sin(tx) cos(tx)];
-
- [~, Dnl] = inverseKinematics(nano_hexapod, 'AP', AP, 'ARB', ARB);
- Dnl = [Dnl, Dnl];
- otherwise
- warning('Dn_type is not set correctly');
- end
-
- Dn = struct('time', t, 'signals', struct('values', Dn));
- Dnl = struct('time', t, 'signals', struct('values', Dnl));
-
-micro_hexapod = stewart;
if exist('./mat', 'dir')
if exist('./mat/nass_references.mat', 'file')
- save('mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'Rm', 'Dn', 'Dnl', 'args', 'Ts', '-append');
+ save('mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'args', 'Ts', '-append');
else
- save('mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'Rm', 'Dn', 'Dnl', 'args', 'Ts');
+ save('mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'args', 'Ts');
end
elseif exist('./matlab', 'dir')
if exist('./matlab/mat/nass_references.mat', 'file')
- save('matlab/mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'Rm', 'Dn', 'Dnl', 'args', 'Ts', '-append');
+ save('matlab/mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'args', 'Ts', '-append');
else
- save('matlab/mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'Rm', 'Dn', 'Dnl', 'args', 'Ts');
+ save('matlab/mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'args', 'Ts');
end
end
diff --git a/matlab/src/initializeStewartPlatform.m b/matlab/src/initializeStewartPlatform.m
new file mode 100644
index 0000000..3804edf
--- /dev/null
+++ b/matlab/src/initializeStewartPlatform.m
@@ -0,0 +1,31 @@
+ function [stewart] = initializeStewartPlatform()
+ % initializeStewartPlatform - Initialize the stewart structure
+ %
+ % Syntax: [stewart] = initializeStewartPlatform(args)
+ %
+ % Outputs:
+ % - stewart - A structure with the following sub-structures:
+ % - platform_F -
+ % - platform_M -
+ % - joints_F -
+ % - joints_M -
+ % - struts_F -
+ % - struts_M -
+ % - actuators -
+ % - geometry -
+ % - properties -
+
+ stewart = struct();
+ stewart.platform_F = struct();
+ stewart.platform_M = struct();
+ stewart.joints_F = struct();
+ stewart.joints_M = struct();
+ stewart.struts_F = struct();
+ stewart.struts_M = struct();
+ stewart.actuators = struct();
+ stewart.sensors = struct();
+ stewart.sensors.inertial = struct();
+ stewart.sensors.force = struct();
+ stewart.sensors.relative = struct();
+ stewart.geometry = struct();
+ stewart.kinematics = struct();
diff --git a/matlab/src/initializeStewartPose.m b/matlab/src/initializeStewartPose.m
new file mode 100644
index 0000000..101a553
--- /dev/null
+++ b/matlab/src/initializeStewartPose.m
@@ -0,0 +1,27 @@
+ function [stewart] = initializeStewartPose(stewart, args)
+ % initializeStewartPose - Determine the initial stroke in each leg to have the wanted pose
+ % It uses the inverse kinematic
+ %
+ % Syntax: [stewart] = initializeStewartPose(stewart, args)
+ %
+ % Inputs:
+ % - stewart - A structure with the following fields
+ % - Aa [3x6] - The positions ai expressed in {A}
+ % - Bb [3x6] - The positions bi expressed in {B}
+ % - args - Can have the following fields:
+ % - AP [3x1] - The wanted position of {B} with respect to {A}
+ % - ARB [3x3] - The rotation matrix that gives the wanted orientation of {B} with respect to {A}
+ %
+ % Outputs:
+ % - stewart - updated Stewart structure with the added fields:
+ % - actuators.Leq [6x1] - The 6 needed displacement of the struts from the initial position in [m] to have the wanted pose of {B} w.r.t. {A}
+
+ arguments
+ stewart
+ args.AP (3,1) double {mustBeNumeric} = zeros(3,1)
+ args.ARB (3,3) double {mustBeNumeric} = eye(3)
+ end
+
+ [Li, dLi] = inverseKinematics(stewart, 'AP', args.AP, 'ARB', args.ARB);
+
+ stewart.actuators.Leq = dLi;
diff --git a/matlab/src/initializeStrutDynamics.m b/matlab/src/initializeStrutDynamics.m
new file mode 100644
index 0000000..26984f5
--- /dev/null
+++ b/matlab/src/initializeStrutDynamics.m
@@ -0,0 +1,49 @@
+ function [stewart] = initializeStrutDynamics(stewart, args)
+ % initializeStrutDynamics - Add Stiffness and Damping properties of each strut
+ %
+ % Syntax: [stewart] = initializeStrutDynamics(args)
+ %
+ % Inputs:
+ % - args - Structure with the following fields:
+ % - K [6x1] - Stiffness of each strut [N/m]
+ % - C [6x1] - Damping of each strut [N/(m/s)]
+ %
+ % Outputs:
+ % - stewart - updated Stewart structure with the added fields:
+ % - actuators.type = 1
+ % - actuators.K [6x1] - Stiffness of each strut [N/m]
+ % - actuators.C [6x1] - Damping of each strut [N/(m/s)]
+
+ arguments
+ stewart
+ args.type char {mustBeMember(args.type,{'classical', 'amplified'})} = 'classical'
+ args.K (6,1) double {mustBeNumeric, mustBeNonnegative} = 20e6*ones(6,1)
+ args.C (6,1) double {mustBeNumeric, mustBeNonnegative} = 2e1*ones(6,1)
+ args.k1 (6,1) double {mustBeNumeric} = 1e6*ones(6,1)
+ args.ke (6,1) double {mustBeNumeric} = 5e6*ones(6,1)
+ args.ka (6,1) double {mustBeNumeric} = 60e6*ones(6,1)
+ args.c1 (6,1) double {mustBeNumeric} = 10*ones(6,1)
+ args.F_gain (6,1) double {mustBeNumeric} = 1*ones(6,1)
+ args.me (6,1) double {mustBeNumeric} = 0.01*ones(6,1)
+ args.ma (6,1) double {mustBeNumeric} = 0.01*ones(6,1)
+ end
+
+ if strcmp(args.type, 'classical')
+ stewart.actuators.type = 1;
+ elseif strcmp(args.type, 'amplified')
+ stewart.actuators.type = 2;
+ end
+
+ stewart.actuators.K = args.K;
+ stewart.actuators.C = args.C;
+
+ stewart.actuators.k1 = args.k1;
+ stewart.actuators.c1 = args.c1;
+
+ stewart.actuators.ka = args.ka;
+ stewart.actuators.ke = args.ke;
+
+ stewart.actuators.F_gain = args.F_gain;
+
+ stewart.actuators.ma = args.ma;
+ stewart.actuators.me = args.me;
diff --git a/matlab/src/inverseKinematics.m b/matlab/src/inverseKinematics.m
new file mode 100644
index 0000000..ec319fe
--- /dev/null
+++ b/matlab/src/inverseKinematics.m
@@ -0,0 +1,36 @@
+ function [Li, dLi] = inverseKinematics(stewart, args)
+ % inverseKinematics - Compute the needed length of each strut to have the wanted position and orientation of {B} with respect to {A}
+ %
+ % Syntax: [stewart] = inverseKinematics(stewart)
+ %
+ % Inputs:
+ % - stewart - A structure with the following fields
+ % - geometry.Aa [3x6] - The positions ai expressed in {A}
+ % - geometry.Bb [3x6] - The positions bi expressed in {B}
+ % - geometry.l [6x1] - Length of each strut
+ % - args - Can have the following fields:
+ % - AP [3x1] - The wanted position of {B} with respect to {A}
+ % - ARB [3x3] - The rotation matrix that gives the wanted orientation of {B} with respect to {A}
+ %
+ % Outputs:
+ % - Li [6x1] - The 6 needed length of the struts in [m] to have the wanted pose of {B} w.r.t. {A}
+ % - dLi [6x1] - The 6 needed displacement of the struts from the initial position in [m] to have the wanted pose of {B} w.r.t. {A}
+
+ arguments
+ stewart
+ args.AP (3,1) double {mustBeNumeric} = zeros(3,1)
+ args.ARB (3,3) double {mustBeNumeric} = eye(3)
+ end
+
+ assert(isfield(stewart.geometry, 'Aa'), 'stewart.geometry should have attribute Aa')
+ Aa = stewart.geometry.Aa;
+
+ assert(isfield(stewart.geometry, 'Bb'), 'stewart.geometry should have attribute Bb')
+ Bb = stewart.geometry.Bb;
+
+ assert(isfield(stewart.geometry, 'l'), 'stewart.geometry should have attribute l')
+ l = stewart.geometry.l;
+
+ Li = sqrt(args.AP'*args.AP + diag(Bb'*Bb) + diag(Aa'*Aa) - (2*args.AP'*Aa)' + (2*args.AP'*(args.ARB*Bb))' - diag(2*(args.ARB*Bb)'*Aa));
+
+ dLi = Li-l;
diff --git a/matlab/ustation_simscape.slx b/matlab/ustation_simscape.slx
index 83e90c6..a43ec14 100644
Binary files a/matlab/ustation_simscape.slx and b/matlab/ustation_simscape.slx differ
diff --git a/simscape-micro-station.org b/simscape-micro-station.org
index 6f4258f..e293b7b 100644
--- a/simscape-micro-station.org
+++ b/simscape-micro-station.org
@@ -43,15 +43,9 @@
#+PROPERTY: header-args:latex+ :mkdirp yes
#+PROPERTY: header-args:latex+ :output-dir figs
#+PROPERTY: header-args:latex+ :post pdf2svg(file=*this*, ext="png")
-:END:
-
-#+begin_export html
-
- This report is also available as a pdf.
-
-#+end_export
#+latex: \clearpage
+:END:
* Build :noexport:
#+NAME: startblock
@@ -112,13 +106,17 @@ From modal analysis: validation of the multi-body model.
*Notes*:
- Do not talk about Nano-Hexapod yet
- Do not talk about external metrology
+- Therefore, do not talk about computation of the sample position / error
Based on:
-- [ ] [[file:~/Cloud/work-projects/ID31-NASS/matlab/nass-simscape/org/kinematics.org][kinematics]]
-- [ ] [[file:~/Cloud/work-projects/ID31-NASS/matlab/nass-simscape/org/simscape_subsystems.org][simscape_subsystems]]: general presentation of the micro-station. Used model: solid body + joints. Presentation of each stage.
-- [ ] [[file:~/Cloud/work-projects/ID31-NASS/documents/work-package-1/work-package-1.org::*Specification of requirements][Specification of requirements]]
-- [ ] [[file:~/Cloud/work-projects/ID31-NASS/matlab/nass-simscape/org/identification.org][identification]]: comparison of measurements and simscape model (not so good?)
+- [X] [[file:~/Cloud/work-projects/ID31-NASS/matlab/nass-simscape/org/kinematics.org][kinematics]]: compute sample's motion from each stage motion
+- [X] [[file:~/Cloud/work-projects/ID31-NASS/matlab/nass-simscape/org/simscape_subsystems.org][simscape_subsystems]]: general presentation of the micro-station. Used model: solid body + joints. Presentation of each stage.
+- [X] [[file:~/Cloud/work-projects/ID31-NASS/documents/work-package-1/work-package-1.org::*Specification of requirements][Specification of requirements]]
+- [X] [[file:~/Cloud/work-projects/ID31-NASS/matlab/nass-simscape/org/identification.org][identification]]: comparison of measurements and simscape model (not so good?)
+- [ ] file:/home/thomas/Cloud/meetings/esrf-meetings/2018-04-24-Simscape-Model/2018-04-24-Simscape-Model.pdf
- [ ] [[file:~/Cloud/work-projects/ID31-NASS/matlab/nass-simscape/org/experiments.org][experiments]]: simulation of experiments with the Simscape model
+- [ ] Disturbances: Similar to what was done for the uniaxial model (the same?)
+ - [[file:~/Cloud/work-projects/ID31-NASS/matlab/nass-simscape/org/disturbances.org::+TITLE: Identification of the disturbances]]
- [ ] Measurement of disturbances / things that will have to be corrected using the NASS:
- [ ] [[file:~/Cloud/work-projects/ID31-NASS/matlab/nass-measurements/static-to-dynamic/index.org]]
- [ ] [[file:~/Cloud/work-projects/ID31-NASS/matlab/nass-measurements/disturbance-control-system/index.org]]
@@ -168,7 +166,14 @@ initializeController( 'type', 'open-loop');
** TODO [#B] Make good "init" for the Simscape model
-** TODO [#C] Verify that we get "correct" compliance
+** TODO [#A] Verify that we get "correct" compliance
+SCHEDULED: <2024-10-30 Wed>
+
+** TODO [#B] Just keep smallest number of variants for each stage
+
+- [ ] rigid
+- [ ] flexible
+- [X] Init => Removed
* Introduction :ignore:
@@ -224,11 +229,444 @@ initializeController( 'type', 'open-loop');
<>
#+end_src
-** Granite
-** Translation Stage
-** Tilt Stage
-** Spindle
-** Micro-Hexapod
+** Motion Stages
+*** Translation Stage
+*** Tilt Stage
+*** Spindle
+*** Micro-Hexapod
+** Specification for each stage
+ <>
+
+For each stage, after a quick presentation, the specifications (stroke, precision, ...) of the stage, the metrology used with that stage and the parasitic motions associated to it are given.
+
+*** Translation along Y
+**** Presentation
+This is the first stage, it is fixed directly on the granite.
+In order to minimize the parasitic motions, two cylinders are used to guide the stage.
+The motor used to drive the stage is one linear motor.
+The 3D model of this translation stage is shown figure ref:fig:stage_translation.
+
+#+name: fig:stage_translation
+#+caption: Translation stage
+[[./figures/stages/stage_translation.pdf]]
+
+**** Specifications
+#+attr_latex: :align |c|c|c|c|c| :placement [!htpb]
+#+CAPTION: Specifications for the translation stage along Y
+#+NAME: fig:spec-t-y
+|--------+------------------------+--------------------------+--------------+--------------|
+| Motion | Mode | Stroke | Repetability | MIM[fn:3] |
+|--------+------------------------+--------------------------+--------------+--------------|
+| $T_y$ | P[fn:1]/S[fn:2] | $\pm5 mm$ | $0.04 \mu m$ | $0.02 \mu m$ |
+| | rotation stage along Y | ($\pm10 mm$ if possible) | | |
+|--------+------------------------+--------------------------+--------------+--------------|
+
+**** Metrology
+A linear digital encoder is used to measure the displacement of the translation stage along the y axis.
+
+**** Parasitic motions
+#+attr_latex: :align |c|c|c| :placement [!htpb]
+#+CAPTION: Parasitic motions for the translation stage along Y
+#+NAME: fig:parasitic-motions-t-y
+|--------------------+-----------------------+------------------------------|
+| Axial Motion ($y$) | Radial Motion ($y-z$) | Rotation motion ($\theta-z$) |
+|--------------------+-----------------------+------------------------------|
+| $10nm$ | $20nm$ | $< 1.7 \mu rad$ |
+|--------------------+-----------------------+------------------------------|
+
+*** Rotation around Y
+**** Presentation
+This stage is mainly use for the reflectivity experiment. This permit to make the sample rotates around the y axis.
+The rotation axis should be parallel to the y-axis and cross the X-ray.
+
+As it is located below the Spindle, it make the axis of rotation of the spindle to also tilt with respect to the X-ray.
+
+4 joints are used in order to pre-stress the system.
+
+The model of the stage is shown figure ref:fig:stage_tilt.
+
+#+name: fig:stage_tilt
+#+caption: Tilt Stage
+[[./figures/stages/stage_tilt.pdf]]
+
+**** Specifications
+#+attr_latex: :align |c|c|c|c|c| :placement [!htpb]
+#+CAPTION: Specifications for the rotation stage along Y
+#+NAME: fig:spec-r-y
+|------------+------+----------------------+--------------+-------------|
+| Motion | Mode | Stroke | Repetability | MIM |
+|------------+------+----------------------+--------------+-------------|
+| $\theta_y$ | S | $\pm51 mrad$ | $5 \mu rad$ | $2 \mu rad$ |
+| | | Speed: $\pm 3^o/min$ | | |
+|------------+------+----------------------+--------------+-------------|
+
+**** Metrology
+Two linear digital encoders are used (one on each side).
+
+**** Parasitic motions
+#+attr_latex: :align |c|c|c| :placement [!htpb]
+#+CAPTION: Parasitic motions for the rotation stage along Y
+#+NAME: fig:parasitic-motions-r-y
+|-------------------+--------------------+---------------|
+| Axial Error ($y$) | Radial Error ($z$) | Tilt error () |
+|-------------------+--------------------+---------------|
+| $0.5\mu m$ | $10nm$ | $1.5 \mu rad$ |
+|-------------------+--------------------+---------------|
+
+*** Spindle
+**** Presentation
+The Spindle consist of one stator (attached to the tilt stage) and one rotor.
+
+The rotor is separated from the stator thanks to an air bearing.
+
+The spindle is represented figure ref:fig:stage_spindle.
+
+It has been developed by Lab-Leuven[fn:5].
+
+#+name: fig:stage_spindle
+#+caption: Spindle
+[[./figures/stages/stage_spindle.pdf]]
+
+**** Specifications
+#+attr_latex: :align |c|c|c|c|c| :placement [!htpb]
+#+CAPTION: Specifications for the Spindle
+#+NAME: fig:spec-r-y
+|------------+------+----------------------+--------------+-------------|
+| Motion | Mode | Stroke | Repetability | MIM |
+|------------+------+----------------------+--------------+-------------|
+| $\theta_z$ | S | $\pm51 mrad$ | $5 \mu rad$ | $2 \mu rad$ |
+| | | Speed: $\pm 3^o/min$ | | |
+|------------+------+----------------------+--------------+-------------|
+
+**** Metrology
+There is an incremental rotation encoder.
+
+**** Parasitic motions
+#+attr_latex: :align |c|c| :placement [!htpb]
+#+CAPTION: Parasitic motions for the Spindle
+#+NAME: fig:parasitic-motions-r-z
+|------------------------+----------------------|
+| Radial Error ($x$-$y$) | Vertical Error ($z$) |
+|------------------------+----------------------|
+| $0.33\mu m$ | $0.07\mu m$ |
+|------------------------+----------------------|
+
+More complete measurements have been conducted at the PEL[fn:7].
+
+*** Long Stroke Hexapod
+**** Presentation
+The long stroke hexapod consists of 6 legs, each composed of:
+- one linear actuators
+- one limit switch
+- one absolute linear encoder
+- one ball joint at each side, one is fixed on the fixed platform, the other on the mobile platform
+
+This long stroke hexapod has been developed by Symetrie[fn:4] and is shown figure ref:fig:stage_hexapod.
+
+#+name: fig:stage_hexapod
+#+caption: Hexapod Symetrie
+[[./figures/stages/stage_hexapod.pdf]]
+
+**** Specifications
+#+attr_latex: :align |c|c|c|c|c| :placement [!htpb]
+#+CAPTION: Specifications for the long stroke hexapod
+#+NAME: fig:spec-hexa
+|------------------+--------------+----------------+--------------+---------------|
+| Motion | Stroke | Repetability | MIM | Stiffness |
+|------------------+--------------+----------------+--------------+---------------|
+| $T_{\mu_x}$ | $\pm10mm$ | $\pm1\mu m$ | $0.5\mu m$ | $>12N/\mu m$ |
+| $T_{\mu_y}$ | $\pm10mm$ | $\pm1\mu m$ | $0.5\mu m$ | $>12N/\mu m$ |
+| $T_{\mu_z}$ | $\pm10mm$ | $\pm1\mu m$ | $0.5\mu m$ | $>135N/\mu m$ |
+| $\theta_{\mu_x}$ | $\pm3 deg$ | $\pm5 \mu rad$ | $2.5\mu rad$ | |
+| $\theta_{\mu_y}$ | $\pm3 deg$ | $\pm5 \mu rad$ | $2.5\mu rad$ | |
+| $\theta_{\mu_z}$ | $\pm0.5 deg$ | $\pm5 \mu rad$ | $2.5\mu rad$ | |
+|------------------+--------------+----------------+--------------+---------------|
+
+**** Metrology
+The metrology consist of one absolute linear encoder in each leg.
+
+**** Parasitic motions
+#+attr_latex: :align |c|c|c| :placement [!htpb]
+#+CAPTION: Parasitic motions for the Spindle
+#+NAME: fig:parasitic-motions-r-z
+|------------------+--------------+----------------|
+| Movement | Resolution | Repeatability |
+|------------------+--------------+----------------|
+| $T_{\mu_x}$ | $0.5\mu m$ | $\pm 1\mu m$ |
+| $T_{\mu_y}$ | $0.5\mu m$ | $\pm 1\mu m$ |
+| $T_{\mu_z}$ | $0.1\mu m$ | $\pm 1\mu m$ |
+| $\theta_{\mu_x}$ | $2.5\mu rad$ | $\pm 4\mu rad$ |
+| $\theta_{\mu_y}$ | $2.5\mu rad$ | $\pm 4\mu rad$ |
+|------------------+--------------+----------------|
+*** Short Stroke Hexapod
+**** Presentation
+This last stage is located just below the sample to study.
+This is the only stage that is not yet build nor designed.
+
+**** Specifications
+#+attr_latex: :align |c|c|c|c|c| :placement [!htpb]
+#+CAPTION: Specifications for the nano-stage
+#+NAME: fig:spec-nano
+|------------------+----------------+--------------+-------|
+| Motion | Stroke | Repetability | MIM |
+|------------------+----------------+--------------+-------|
+| $T_{\nu_x}$ | $\pm10\mu m$ | $10nm$ | $3nm$ |
+| $T_{\nu_y}$ | $\pm10\mu m$ | $10nm$ | $3nm$ |
+| $T_{\nu_z}$ | $\pm10\mu m$ | $10nm$ | $3nm$ |
+| $\theta_{\nu_x}$ | $\pm10\mu rad$ | $1.7\mu rad$ | |
+| $\theta_{\nu_y}$ | $\pm10\mu rad$ | $1.7\mu rad$ | |
+| $\theta_{\nu_z}$ | $\pm10\mu rad$ | | |
+|------------------+----------------+--------------+-------|
+
+**** Dimensions
+- Bottom plate :
+ - Inner diameter: $>150mm$
+ - External diameter: $<305mm$
+- Top plate
+ - External diameter: $<300mm$
+- Height: $90mm$
+- Location of the rotation point: Centered, at $175mm$ above the top platform
+
+** Compute sample's motion from stage motion
+*** Introduction :ignore:
+#+begin_quote
+Rx = [1 0 0;
+ 0 cos(t) -sin(t);
+ 0 sin(t) cos(t)];
+
+Ry = [ cos(t) 0 sin(t);
+ 0 1 0;
+ -sin(t) 0 cos(t)];
+
+Rz = [cos(t) -sin(t) 0;
+ sin(t) cos(t) 0;
+ 0 0 1];
+#+end_quote
+
+Let's define the following frames:
+- $\{W\}$ the frame that is *fixed to the granite* and its origin at the theoretical meeting point between the X-ray and the spindle axis.
+- $\{S\}$ the frame *attached to the sample* (in reality attached to the top platform of the nano-hexapod) with its origin at 175mm above the top platform of the nano-hexapod.
+ Its origin is $O_S$.
+- $\{T\}$ the theoretical wanted frame that correspond to the wanted pose of the frame $\{S\}$.
+ $\{T\}$ is computed from the wanted position of each stage. It is thus theoretical and does not correspond to a real position.
+ The origin of $T$ is $O_T$ and is the wanted position of the sample.
+
+Thus:
+- the *measurement* of the position of the sample corresponds to ${}^W O_S = \begin{bmatrix} {}^WP_{x,m} & {}^WP_{y,m} & {}^WP_{z,m} \end{bmatrix}^T$ in translation and to $\theta_m {}^W\bm{s}_m = \theta_m \cdot \begin{bmatrix} {}^Ws_{x,m} & {}^Ws_{y,m} & {}^Ws_{z,m} \end{bmatrix}^T$ in rotations
+- the *wanted position* of the sample expressed w.r.t. the granite is ${}^W O_T = \begin{bmatrix} {}^WP_{x,r} & {}^WP_{y,r} & {}^WP_{z,r} \end{bmatrix}^T$ in translation and to $\theta_r {}^W\bm{s}_r = \theta_r \cdot \begin{bmatrix} {}^Ws_{x,r} & {}^Ws_{y,r} & {}^Ws_{z,r} \end{bmatrix}^T$ in rotations
+
+*** Wanted Position of the Sample with respect to the Granite
+Let's define the wanted position of each stage.
+#+begin_src matlab
+ Ty = 0; % [m]
+ Ry = 3*pi/180; % [rad]
+ Rz = 180*pi/180; % [rad]
+
+ % Hexapod (first consider only translations)
+ Thx = 0; % [m]
+ Thy = 0; % [m]
+ Thz = 0; % [m]
+#+end_src
+
+Now, we compute the corresponding wanted translation and rotation of the sample with respect to the granite frame $\{W\}$.
+This corresponds to ${}^WO_T$ and $\theta_m {}^Ws_m$.
+
+To do so, we have to define the homogeneous transformation for each stage.
+#+begin_src matlab
+ % Translation Stage
+ Rty = [1 0 0 0;
+ 0 1 0 Ty;
+ 0 0 1 0;
+ 0 0 0 1];
+
+ % Tilt Stage - Pure rotating aligned with Ob
+ Rry = [ cos(Ry) 0 sin(Ry) 0;
+ 0 1 0 0;
+ -sin(Ry) 0 cos(Ry) 0;
+ 0 0 0 1];
+
+ % Spindle - Rotation along the Z axis
+ Rrz = [cos(Rz) -sin(Rz) 0 0 ;
+ sin(Rz) cos(Rz) 0 0 ;
+ 0 0 1 0 ;
+ 0 0 0 1 ];
+
+ % Micro-Hexapod (only rotations first)
+ Rh = [1 0 0 Thx ;
+ 0 1 0 Thy ;
+ 0 0 1 Thz ;
+ 0 0 0 1 ];
+#+end_src
+
+We combine the individual homogeneous transformations into one homogeneous transformation for all the station.
+#+begin_src matlab
+ Ttot = Rty*Rry*Rrz*Rh;
+#+end_src
+
+Using this homogeneous transformation, we can compute the wanted position and orientation of the sample with respect to the granite.
+
+Translation.
+#+begin_src matlab
+ WOr = Ttot*[0;0;0;1];
+ WOr = WOr(1:3);
+#+end_src
+
+Rotation.
+#+begin_src matlab
+ thetar = acos((trace(Ttot(1:3, 1:3))-1)/2)
+ if thetar == 0
+ WSr = [0; 0; 0];
+ else
+ [V, D] = eig(Ttot(1:3, 1:3));
+ WSr = thetar*V(:, abs(diag(D) - 1) < eps(1));
+ end
+#+end_src
+
+#+begin_src matlab
+ WPr = [WOr ; WSr];
+#+end_src
+
+*** Measured Position of the Sample with respect to the Granite
+The measurement of the position of the sample using the metrology system gives the position and orientation of the sample with respect to the granite.
+#+begin_src matlab
+ % Measurements: Xm, Ym, Zm, Rx, Ry, Rz
+ Dxm = 0; % [m]
+ Dym = 0; % [m]
+ Dzm = 0; % [m]
+
+ Rxm = 0*pi/180; % [rad]
+ Rym = 0*pi/180; % [rad]
+ Rzm = 180*pi/180; % [rad]
+#+end_src
+
+Let's compute the corresponding orientation using screw axis.
+#+begin_src matlab
+ Trxm = [1 0 0;
+ 0 cos(Rxm) -sin(Rxm);
+ 0 sin(Rxm) cos(Rxm)];
+ Trym = [ cos(Rym) 0 sin(Rym);
+ 0 1 0;
+ -sin(Rym) 0 cos(Rym)];
+ Trzm = [cos(Rzm) -sin(Rzm) 0;
+ sin(Rzm) cos(Rzm) 0;
+ 0 0 1];
+
+ STw = [[ Trym*Trxm*Trzm , [Dxm; Dym; Dzm]]; 0 0 0 1];
+#+end_src
+
+We then obtain the orientation measurement in the form of screw coordinate $\theta_m ({}^Ws_{x,m},\ {}^Ws_{y,m},\ {}^Ws_{z,m})^T$ where:
+- $\theta_m = \cos^{-1} \frac{\text{Tr}(R) - 1}{2}$
+- ${}^W\bm{s}_m$ is the eigen vector of the rotation matrix $R$ corresponding to the eigen value $\lambda = 1$
+
+#+begin_src matlab
+ thetam = acos((trace(STw(1:3, 1:3))-1)/2); % [rad]
+ if thetam == 0
+ WSm = [0; 0; 0];
+ else
+ [V, D] = eig(STw(1:3, 1:3));
+ WSm = thetam*V(:, abs(diag(D) - 1) < eps(1));
+ end
+#+end_src
+
+#+begin_src matlab
+ WPm = [Dxm ; Dym ; Dzm ; WSm];
+#+end_src
+
+*** Positioning Error with respect to the Granite
+The wanted position expressed with respect to the granite is ${}^WO_T$ and the measured position with respect to the granite is ${}^WO_S$, thus the *position error* expressed in $\{W\}$ is
+\[ {}^W E = {}^W O_T - {}^W O_S \]
+The same is true for rotations:
+\[ \theta_\epsilon {}^W\bm{s}_\epsilon = \theta_r {}^W\bm{s}_r - \theta_m {}^W\bm{s}_m \]
+
+#+begin_src matlab
+ WPe = WPr - WPm;
+#+end_src
+
+#+begin_quote
+Now we want to express this error in a frame attached to the *base of the nano-hexapod* with its origin at the same point where the Jacobian of the nano-hexapod is computed (175mm above the top platform + 90mm of total height of the nano-hexapod).
+
+Or maybe should we want to express this error with respect to the *top platform of the nano-hexapod*?
+We are measuring the position of the top-platform, and we don't know exactly the position of the bottom platform.
+We could compute the position of the bottom platform in two ways:
+- from the encoders of each stage
+- from the measurement of the nano-hexapod top platform + the internal metrology in the nano-hexapod (capacitive sensors e.g)
+
+A third option is to say that the maximum stroke of the nano-hexapod is so small that the error should no change to much by the change of base.
+#+end_quote
+
+*** Position Error Expressed in the Nano-Hexapod Frame
+We now want the position error to be expressed in $\{S\}$ (the frame attach to the sample) for control:
+\[ {}^S E = {}^S T_W \cdot {}^W E \]
+
+Thus we need to compute the homogeneous transformation ${}^ST_W$.
+Fortunately, this homogeneous transformation can be computed from the measurement of the sample position and orientation with respect to the granite.
+#+begin_src matlab
+ Trxm = [1 0 0;
+ 0 cos(Rxm) -sin(Rxm);
+ 0 sin(Rxm) cos(Rxm)];
+ Trym = [ cos(Rym) 0 sin(Rym);
+ 0 1 0;
+ -sin(Rym) 0 cos(Rym)];
+ Trzm = [cos(Rzm) -sin(Rzm) 0;
+ sin(Rzm) cos(Rzm) 0;
+ 0 0 1];
+
+ STw = [[ Trym*Trxm*Trzm , [Dxm; Dym; Dzm]]; 0 0 0 1];
+#+end_src
+
+Translation Error.
+#+begin_src matlab
+ SEm = STw * [WPe(1:3); 0];
+ SEm = SEm(1:3);
+#+end_src
+
+Rotation Error.
+#+begin_src matlab
+ SEr = STw * [WPe(4:6); 0];
+ SEr = SEr(1:3);
+#+end_src
+
+#+begin_src matlab
+ Etot = [SEm ; SEr]
+#+end_src
+*** Another try
+Let's denote:
+- $\{W\}$ the initial fixed frame
+- $\{R\}$ the reference frame corresponding to the wanted pose of the sample
+- $\{M\}$ the frame corresponding to the measured pose of the sample
+
+We have then computed:
+- ${}^WT_R$
+- ${}^WT_M$
+
+We have:
+\begin{align}
+ {}^MT_R &= {}^MT_W {}^WT_R \\
+ &= {}^WT_M^t {}^WT_R
+\end{align}
+
+#+begin_src matlab
+ MTr = STw'*Ttot;
+#+end_src
+
+Position error:
+#+begin_src matlab
+ MTr(1:3, 1:4)*[0; 0; 0; 1]
+#+end_src
+
+Orientation error:
+#+begin_src matlab
+ MTr(1:3, 1:3)
+#+end_src
+
+*** Verification
+How can we verify that the computation is correct?
+Options:
+- Test with simscape multi-body
+ - Impose motion on each stage
+ - Measure the position error w.r.t. the NASS
+ - Compare with the computation
+
* Stage Modeling
:PROPERTIES:
:HEADER-ARGS:matlab+: :tangle matlab/.m
@@ -249,6 +687,10 @@ Finally, this should help to tune the parameters of the model such that the dyna
# - Compare model and measurement
** Matlab Init :noexport:ignore:
+#+begin_src matlab
+%% .m
+#+end_src
+
#+begin_src matlab :tangle no :exports none :results silent :noweb yes :var current_dir=(file-name-directory buffer-file-name)
<>
#+end_src
@@ -265,11 +707,16 @@ Finally, this should help to tune the parameters of the model such that the dyna
<>
#+end_src
+#+begin_src matlab :noweb yes
+<>
+#+end_src
+
#+begin_src matlab :noweb yes
<>
#+end_src
** Some notes about the Simscape Model
+
The Simscape Model of the micro-station consists of several solid bodies:
- Bottom Granite
- Top Granite
@@ -285,257 +732,109 @@ Then, the solid bodies are connected with springs and dampers.
Some of the springs and dampers values can be estimated from the joints/stages specifications, however, we here prefer to tune these values based on the measurements.
** Compare with measurements at the CoM of each element
-*** Matlab Init :noexport:ignore:
-#+begin_src matlab :tangle no :exports none :results silent :noweb yes :var current_dir=(file-name-directory buffer-file-name)
- <>
-#+end_src
-
-#+begin_src matlab :exports none :results silent :noweb yes
- <>
-#+end_src
-
-#+begin_src matlab :tangle no
- simulinkproject('../');
-#+end_src
-
-*** Prepare the Simulation
-We load the configuration.
#+begin_src matlab
- load('mat/conf_simulink.mat');
+%% We load the configuration.
+load('conf_simulink.mat');
+
+% We set a small =StopTime=.
+set_param(conf_simulink, 'StopTime', '0.5');
+
+%% We initialize all the stages.
+initializeGround( 'type', 'rigid');
+initializeGranite( 'type', 'modal-analysis');
+initializeTy( 'type', 'modal-analysis');
+initializeRy( 'type', 'modal-analysis');
+initializeRz( 'type', 'modal-analysis');
+initializeMicroHexapod('type', 'modal-analysis');
+
+initializeLoggingConfiguration('log', 'none');
+
+initializeReferences();
+initializeDisturbances('enable', false);
#+end_src
-We set a small =StopTime=.
-#+begin_src matlab
- set_param(conf_simulink, 'StopTime', '0.5');
-#+end_src
-
-We initialize all the stages.
-#+begin_src matlab
- initializeGround( 'type', 'rigid');
- initializeGranite( 'type', 'modal-analysis');
- initializeTy( 'type', 'modal-analysis');
- initializeRy( 'type', 'modal-analysis');
- initializeRz( 'type', 'modal-analysis');
- initializeMicroHexapod('type', 'modal-analysis');
- initializeAxisc( 'type', 'flexible');
-
- initializeMirror( 'type', 'none');
- initializeNanoHexapod( 'type', 'none');
- initializeSample( 'type', 'none');
-
- initializeController( 'type', 'open-loop');
-
- initializeLoggingConfiguration('log', 'none');
-
- initializeReferences();
- initializeDisturbances('enable', false);
-#+end_src
-
-*** Estimate the position of the CoM of each solid and compare with the one took for the Measurement Analysis
-Thanks to the [[https://fr.mathworks.com/help/physmod/sm/ref/inertiasensor.html][Inertia Sensor]] simscape block, it is possible to estimate the position of the Center of Mass of a solid body with respect to a defined frame.
-
-#+begin_src matlab
- sim('nass_model')
-#+end_src
-
-The results are shown in the table [[tab:com_simscape]].
-
-#+begin_src matlab :exports results :results value table replace :tangle no :post addhdr(*this*)
- stages_com = 1e3*[granite_bot_com.Data(end, :) ;
- granite_top_com.Data(end, :) ;
- ty_com.Data(end, :) ;
- ry_com.Data(end, :) ;
- rz_com.Data(end, :) ;
- hexa_com.Data(end, :) ]';
-
- data2orgtable(stages_com, {'X [mm]', 'Y [mm]', 'Z [mm]'}, {'granite bot', 'granite top', 'ty', 'ry', 'rz', 'hexa'}, ' %.1f ');
-#+end_src
-
-#+name: tab:com_simscape
-#+caption: Center of Mass of each solid body as defined in Simscape
-#+RESULTS:
-| | granite bot | granite top | ty | ry | rz | hexa |
-|--------+-------------+-------------+--------+--------+--------+--------|
-| X [mm] | 52.4 | 51.7 | 0.9 | -0.1 | 0.0 | -0.0 |
-| Y [mm] | 190.4 | 263.2 | 0.7 | 5.2 | -0.0 | 0.1 |
-| Z [mm] | -1200.0 | -777.1 | -598.9 | -627.7 | -643.2 | -317.1 |
-
-We can compare the obtained center of mass (table [[tab:com_simscape]]) with the one used for the Modal Analysis shown in table [[tab:com_solidworks]].
-
-#+name: tab:com_solidworks
-#+caption: Estimated Center of Mass of each solid body using Solidworks
-| | granite bot | granite top | ty | ry | rz | hexa |
-|--------+-------------+-------------+------+------+------+------|
-| X [mm] | 45 | 52 | 0 | 0 | 0 | -4 |
-| Y [mm] | 144 | 258 | 14 | -5 | 0 | 6 |
-| Z [mm] | -1251 | -778 | -600 | -628 | -580 | -319 |
-
-The results are quite similar.
-The differences can be explained by some differences in the chosen density of the materials or by the fact that not exactly all the same elements have been chosen for each stage.
-
-For instance, on simscape, the fixed part of the translation stage counts for the top granite solid body.
-However, in SolidWorks, this has probably not be included with the top granite.
-
-*** Create a frame at the CoM of each solid body
-Now we use one =inertiasensor= block connected on each solid body that measured the center of mass of this solid with respect to the same connected frame.
-
-We do that in order to position an accelerometer on the Simscape model at this particular point.
-
-#+begin_src matlab
- open('identification/matlab/sim_micro_station_com_estimation.slx')
-#+end_src
-
-#+begin_src matlab
- sim('sim_micro_station_com_estimation')
-#+end_src
-
-#+begin_src matlab :exports results :results value table replace :tangle no :post addhdr(*this*)
- stages_com = 1e3*[granite_bot_com.Data(end, :) ;
- granite_top_com.Data(end, :) ;
- ty_com.Data(end, :) ;
- ry_com.Data(end, :) ;
- rz_com.Data(end, :) ;
- hexa_com.Data(end, :) ]';
-
- data2orgtable(stages_com, {'X [mm]', 'Y [mm]', 'Z [mm]'}, {'granite bot', 'granite top', 'ty', 'ry', 'rz', 'hexa'}, ' %.1f ');
-#+end_src
-
-#+RESULTS:
-| | granite bot | granite top | ty | ry | rz | hexa |
-|--------+-------------+-------------+-------+--------+-------+-------|
-| X [mm] | 0.0 | 51.7 | 0.9 | -0.1 | 0.0 | -0.0 |
-| Y [mm] | 0.0 | 753.2 | 0.7 | 5.2 | -0.0 | 0.1 |
-| Z [mm] | -250.0 | 22.9 | -17.1 | -146.5 | -23.2 | -47.1 |
-
-We now same this for further use:
-#+begin_src matlab
- granite_bot_com = granite_bot_com.Data(end, :)';
- granite_top_com = granite_top_com.Data(end, :)';
- ty_com = ty_com.Data(end, :)';
- ry_com = ry_com.Data(end, :)';
- rz_com = rz_com.Data(end, :)';
- hexa_com = hexa_com.Data(end, :)';
-
- save('./mat/solids_com.mat', 'granite_bot_com', 'granite_top_com', 'ty_com', 'ry_com', 'rz_com', 'hexa_com');
-#+end_src
-
-Then, we use the obtained results to add a =rigidTransform= block in order to create a new frame at the center of mass of each solid body.
-
-*** Identification of the dynamics of the Simscape Model
We now use a new Simscape Model where 6DoF inertial sensors are located at the Center of Mass of each solid body.
-#+begin_src matlab
- % load('mat/solids_com.mat', 'granite_bot_com', 'granite_top_com', 'ty_com', 'ry_com', 'rz_com', 'hexa_com');
-#+end_src
-
-#+begin_src matlab
- open('nass_model.slx')
-#+end_src
-
We use the =linearize= function in order to estimate the dynamics from forces applied on the Translation stage at the same position used for the real modal analysis to the inertial sensors.
#+begin_src matlab
- %% Options for Linearized
- options = linearizeOptions;
- options.SampleTime = 0;
+%% Identification
+% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Micro-Station/Translation Stage/Modal Analysis/F_hammer'], 1, 'openinput'); io_i = io_i + 1;
+io(io_i) = linio([mdl, '/Micro-Station/Granite/Modal Analysis/accelerometer'], 1, 'openoutput'); io_i = io_i + 1;
+io(io_i) = linio([mdl, '/Micro-Station/Translation Stage/Modal Analysis/accelerometer'], 1, 'openoutput'); io_i = io_i + 1;
+io(io_i) = linio([mdl, '/Micro-Station/Tilt Stage/Modal Analysis/accelerometer'], 1, 'openoutput'); io_i = io_i + 1;
+io(io_i) = linio([mdl, '/Micro-Station/Spindle/Modal Analysis/accelerometer'], 1, 'openoutput'); io_i = io_i + 1;
+io(io_i) = linio([mdl, '/Micro-Station/Micro Hexapod/Modal Analysis/accelerometer'], 1, 'openoutput'); io_i = io_i + 1;
- %% Name of the Simulink File
- mdl = 'nass_model';
+% Run the linearization
+G_ms = linearize(mdl, io, 0);
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Micro-Station/Translation Stage/Modal Analysis/F_hammer'], 1, 'openinput'); io_i = io_i + 1;
- io(io_i) = linio([mdl, '/Micro-Station/Granite/Modal Analysis/accelerometer'], 1, 'openoutput'); io_i = io_i + 1;
- io(io_i) = linio([mdl, '/Micro-Station/Translation Stage/Modal Analysis/accelerometer'], 1, 'openoutput'); io_i = io_i + 1;
- io(io_i) = linio([mdl, '/Micro-Station/Tilt Stage/Modal Analysis/accelerometer'], 1, 'openoutput'); io_i = io_i + 1;
- io(io_i) = linio([mdl, '/Micro-Station/Spindle/Modal Analysis/accelerometer'], 1, 'openoutput'); io_i = io_i + 1;
- io(io_i) = linio([mdl, '/Micro-Station/Micro Hexapod/Modal Analysis/accelerometer'], 1, 'openoutput'); io_i = io_i + 1;
+% Input/Output definition
+G_ms.InputName = {'Fx', 'Fy', 'Fz'};
+G_ms.OutputName = {'gtop_x', 'gtop_y', 'gtop_z', 'gtop_rx', 'gtop_ry', 'gtop_rz', ...
+ 'ty_x', 'ty_y', 'ty_z', 'ty_rx', 'ty_ry', 'ty_rz', ...
+ 'ry_x', 'ry_y', 'ry_z', 'ry_rx', 'ry_ry', 'ry_rz', ...
+ 'rz_x', 'rz_y', 'rz_z', 'rz_rx', 'rz_ry', 'rz_rz', ...
+ 'hexa_x', 'hexa_y', 'hexa_z', 'hexa_rx', 'hexa_ry', 'hexa_rz'};
+
+% Put the output of G in displacements instead of acceleration
+G_ms = G_ms/s^2;
#+end_src
#+begin_src matlab
- % Run the linearization
- G_ms = linearize(mdl, io, 0);
-
- %% Input/Output definition
- G_ms.InputName = {'Fx', 'Fy', 'Fz'};
- G_ms.OutputName = {'gtop_x', 'gtop_y', 'gtop_z', 'gtop_rx', 'gtop_ry', 'gtop_rz', ...
- 'ty_x', 'ty_y', 'ty_z', 'ty_rx', 'ty_ry', 'ty_rz', ...
- 'ry_x', 'ry_y', 'ry_z', 'ry_rx', 'ry_ry', 'ry_rz', ...
- 'rz_x', 'rz_y', 'rz_z', 'rz_rx', 'rz_ry', 'rz_rz', ...
- 'hexa_x', 'hexa_y', 'hexa_z', 'hexa_rx', 'hexa_ry', 'hexa_rz'};
-#+end_src
-
-The output of =G_ms= is the acceleration of each solid body.
-In order to obtain a displacement, we divide the obtained transfer function by $1/s^{2}$;
-#+begin_src matlab
- G_ms = G_ms/s^2;
-#+end_src
-
-*** Compare with measurements
-We now load the Frequency Response Functions measurements during the Modal Analysis (accessible [[file:../../meas/modal-analysis/index.org][here]]).
-
-#+begin_src matlab
- load('../meas/modal-analysis/mat/frf_coh_matrices.mat', 'freqs');
- load('../meas/modal-analysis/mat/frf_com.mat', 'FRFs_CoM');
-#+end_src
-
-We then compare the measurements with the identified transfer functions using the Simscape Model.
-
-#+begin_src matlab :exports none
- dirs = {'x', 'y', 'z', 'rx', 'ry', 'rz'};
- stages = {'gbot', 'gtop', 'ty', 'ry', 'rz', 'hexa'}
-
- n_stg = 3;
- n_dir = 6; % x, y, z, Rx, Ry, Rz
- n_exc = 2; % x, y, z
-
- f = logspace(0, 3, 1000);
-
- figure;
- hold on;
- plot(freqs, abs(squeeze(FRFs_CoM(6*(n_stg-1) + n_dir, n_exc, :)))./((2*pi*freqs).^2)');
- plot(f, abs(squeeze(freqresp(G_ms([stages{n_stg}, '_', dirs{n_dir}], ['F', dirs{n_exc}]), f, 'Hz'))));
- set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
- ylabel('Amplitude [m/N]');
- hold off;
- xlim([1, 200]);
+%% Load estimated FRF at CoM
+load('/home/thomas/Cloud/work-projects/ID31-NASS/phd-thesis-chapters/A3-micro-station-modal-analysis/matlab/mat/frf_matrix.mat', 'freqs');
+load('/home/thomas/Cloud/work-projects/ID31-NASS/phd-thesis-chapters/A3-micro-station-modal-analysis/matlab/mat/frf_com.mat', 'frfs_CoM');
#+end_src
#+begin_src matlab :exports none
- dirs = {'x', 'y', 'z', 'rx', 'ry', 'rz'};
- stages = {'gtop', 'ty', 'ry', 'rz', 'hexa'}
+%% Compare the two
+dirs = {'x', 'y', 'z', 'rx', 'ry', 'rz'};
+stages = {'gbot', 'gtop', 'ty', 'ry', 'rz', 'hexa'}
- f = logspace(1, 3, 1000);
+n_stg = 3;
+n_dir = 6; % x, y, z, Rx, Ry, Rz
+n_exc = 2; % x, y, z
- figure;
- for n_stg = 1:2
+f = logspace(0, 3, 1000);
+
+figure;
+hold on;
+plot(freqs, abs(squeeze(frfs_CoM(6*(n_stg-1) + n_dir, n_exc, :)))./((2*pi*freqs).^2)');
+plot(f, abs(squeeze(freqresp(G_ms([stages{n_stg}, '_', dirs{n_dir}], ['F', dirs{n_exc}]), f, 'Hz'))));
+set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
+ylabel('Amplitude [m/N]');
+hold off;
+xlim([1, 200]);
+#+end_src
+
+#+begin_src matlab :exports none
+dirs = {'x', 'y', 'z', 'rx', 'ry', 'rz'};
+stages = {'gtop', 'ty', 'ry', 'rz', 'hexa'}
+
+f = logspace(1, 3, 1000);
+
+figure;
+for n_stg = 1:2
for n_dir = 1:3
- subplot(3, 2, (n_dir-1)*2 + n_stg);
- title(['F ', dirs{n_dir}, ' to ', stages{n_stg}, ' ', dirs{n_dir}]);
- hold on;
- plot(freqs, abs(squeeze(FRFs_CoM(6*(n_stg) + n_dir, n_dir, :)))./((2*pi*freqs).^2)');
- plot(f, abs(squeeze(freqresp(G_ms([stages{n_stg}, '_', dirs{n_dir}], ['F', dirs{n_dir}]), f, 'Hz'))));
- set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
- ylabel('Amplitude [m/N]');
- if n_dir == 3
- xlabel('Frequency [Hz]');
- end
- hold off;
- xlim([10, 1000]);
- ylim([1e-12, 1e-6]);
+ subplot(3, 2, (n_dir-1)*2 + n_stg);
+ title(['F ', dirs{n_dir}, ' to ', stages{n_stg}, ' ', dirs{n_dir}]);
+ hold on;
+ plot(freqs, abs(squeeze(frfs_CoM(6*(n_stg) + n_dir, n_dir, :)))./((2*pi*freqs).^2)');
+ plot(f, abs(squeeze(freqresp(G_ms([stages{n_stg}, '_', dirs{n_dir}], ['F', dirs{n_dir}]), f, 'Hz'))));
+ set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
+ ylabel('Amplitude [m/N]');
+ if n_dir == 3
+ xlabel('Frequency [Hz]');
+ end
+ hold off;
+ xlim([10, 1000]);
+ ylim([1e-12, 1e-6]);
end
- end
+end
#+end_src
-#+HEADER: :tangle no :exports results :results none :noweb yes
-#+begin_src matlab :var filepath="figs/identification_comp_bot_stages.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png")
- <>
-#+end_src
-
-#+NAME: fig:identification_comp_bot_stages
-#+CAPTION: caption ([[./figs/identification_comp_bot_stages.png][png]], [[./figs/identification_comp_bot_stages.pdf][pdf]])
-[[file:figs/identification_comp_bot_stages.png]]
-
-
#+begin_src matlab :exports none
dirs = {'x', 'y', 'z', 'rx', 'ry', 'rz'};
stages = {'ry', 'rz', 'hexa'}
@@ -548,7 +847,7 @@ We then compare the measurements with the identified transfer functions using th
subplot(3, 2, (n_dir-1)*2 + n_stg);
title(['F ', dirs{n_dir}, ' to ', stages{n_stg}, ' ', dirs{n_dir}]);
hold on;
- plot(freqs, abs(squeeze(FRFs_CoM(6*(n_stg+2) + n_dir, n_dir, :)))./((2*pi*freqs).^2)');
+ plot(freqs, abs(squeeze(frfs_CoM(6*(n_stg+2) + n_dir, n_dir, :)))./((2*pi*freqs).^2)');
plot(f, abs(squeeze(freqresp(G_ms([stages{n_stg}, '_', dirs{n_dir}], ['F', dirs{n_dir}]), f, 'Hz'))));
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [m/N]');
@@ -562,16 +861,6 @@ We then compare the measurements with the identified transfer functions using th
end
#+end_src
-#+HEADER: :tangle no :exports results :results none :noweb yes
-#+begin_src matlab :var filepath="figs/identification_comp_mid_stages.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png")
- <>
-#+end_src
-
-#+NAME: fig:identification_comp_mid_stages
-#+CAPTION: caption ([[./figs/identification_comp_mid_stages.png][png]], [[./figs/identification_comp_mid_stages.pdf][pdf]])
-[[file:figs/identification_comp_mid_stages.png]]
-
-
#+begin_src matlab :exports none
dirs = {'x', 'y', 'z', 'rx', 'ry', 'rz'};
stages = {'hexa'}
@@ -584,7 +873,7 @@ We then compare the measurements with the identified transfer functions using th
subplot(3, 1, (n_dir-1) + n_stg);
title(['F ', dirs{n_dir}, ' to ', stages{n_stg}, ' ', dirs{n_dir}]);
hold on;
- plot(freqs, abs(squeeze(FRFs_CoM(6*(n_stg+4) + n_dir, n_dir, :)))./((2*pi*freqs).^2)');
+ plot(freqs, abs(squeeze(frfs_CoM(6*(n_stg+4) + n_dir, n_dir, :)))./((2*pi*freqs).^2)');
plot(f, abs(squeeze(freqresp(G_ms([stages{n_stg}, '_', dirs{n_dir}], ['F', dirs{n_dir}]), f, 'Hz'))));
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [m/N]');
@@ -598,114 +887,61 @@ We then compare the measurements with the identified transfer functions using th
end
#+end_src
-#+HEADER: :tangle no :exports results :results none :noweb yes
-#+begin_src matlab :var filepath="figs/identification_comp_top_stages.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png")
- <>
-#+end_src
-
-#+NAME: fig:identification_comp_top_stages
-#+CAPTION: caption ([[./figs/identification_comp_top_stages.png][png]], [[./figs/identification_comp_top_stages.pdf][pdf]])
-[[file:figs/identification_comp_top_stages.png]]
-
-
** Obtained Compliance of the Micro-Station
-*** Matlab Init :noexport:ignore:
-#+begin_src matlab :tangle no :exports none :results silent :noweb yes :var current_dir=(file-name-directory buffer-file-name)
- <>
-#+end_src
-
-#+begin_src matlab :exports none :results silent :noweb yes
- <>
-#+end_src
-
-#+begin_src matlab :tangle no
- simulinkproject('../');
-#+end_src
-
#+begin_src matlab
- open('nass_model.slx')
-#+end_src
+%% Initialize simulation with default parameters (flexible elements)
+initializeGround();
+initializeGranite();
+initializeTy();
+initializeRy();
+initializeRz();
+initializeMicroHexapod('type', 'compliance');
-*** Initialization
-We initialize all the stages with the default parameters.
-#+begin_src matlab
- initializeGround();
- initializeGranite();
- initializeTy();
- initializeRy();
- initializeRz();
- initializeMicroHexapod('type', 'compliance');
-#+end_src
-
-We put nothing on top of the micro-hexapod.
-#+begin_src matlab
- initializeAxisc('type', 'none');
- initializeMirror('type', 'none');
- initializeNanoHexapod('type', 'none');
- initializeSample('type', 'none');
-#+end_src
-
-#+begin_src matlab
- initializeReferences();
- initializeDisturbances();
- initializeController();
- initializeSimscapeConfiguration();
- initializeLoggingConfiguration();
+initializeReferences();
+initializeDisturbances();
+initializeSimscapeConfiguration();
+initializeLoggingConfiguration();
#+end_src
And we identify the dynamics from forces/torques applied on the micro-hexapod top platform to the motion of the micro-hexapod top platform at the same point.
-The obtained compliance is shown in Figure [[fig:compliance_micro_station]].
#+begin_src matlab
- %% Name of the Simulink File
- mdl = 'nass_model';
+%% Identification of the compliance
+% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Micro-Station/Micro Hexapod/Compliance/Fm'], 1, 'openinput'); io_i = io_i + 1; % Direct Forces/Torques applied on the micro-hexapod top platform
+io(io_i) = linio([mdl, '/Micro-Station/Micro Hexapod/Compliance/Dm'], 1, 'output'); io_i = io_i + 1; % Absolute displacement of the top platform
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Micro-Station/Micro Hexapod/Compliance/Fm'], 1, 'openinput'); io_i = io_i + 1; % Direct Forces/Torques applied on the micro-hexapod top platform
- io(io_i) = linio([mdl, '/Micro-Station/Micro Hexapod/Compliance/Dm'], 1, 'output'); io_i = io_i + 1; % Absolute displacement of the top platform
-
- %% Run the linearization
- Gm = linearize(mdl, io, 0);
- Gm.InputName = {'Fmx', 'Fmy', 'Fmz', 'Mmx', 'Mmy', 'Mmz'};
- Gm.OutputName = {'Dx', 'Dy', 'Dz', 'Drx', 'Dry', 'Drz'};
-#+end_src
-
-#+begin_src matlab
- save('../meas/micro-station-compliance/mat/model.mat', 'Gm');
+% Run the linearization
+Gm = linearize(mdl, io, 0);
+Gm.InputName = {'Fmx', 'Fmy', 'Fmz', 'Mmx', 'Mmy', 'Mmz'};
+Gm.OutputName = {'Dx', 'Dy', 'Dz', 'Drx', 'Dry', 'Drz'};
#+end_src
#+begin_src matlab :exports none
- labels = {'$D_x/F_{x}$', '$D_y/F_{y}$', '$D_z/F_{z}$', '$R_{x}/M_{x}$', '$R_{y}/M_{y}$', '$R_{R}/M_{z}$'};
+%% Plot of the compliance curves
+labels = {'$D_x/F_{x}$', '$D_y/F_{y}$', '$D_z/F_{z}$', '$R_{x}/M_{x}$', '$R_{y}/M_{y}$', '$R_{R}/M_{z}$'};
- freqs = logspace(1, 3, 1000);
+freqs = logspace(1, 3, 1000);
- figure;
+figure;
- hold on;
- for i = 1:6
+hold on;
+for i = 1:6
plot(freqs, abs(squeeze(freqresp(Gm(i, i), freqs, 'Hz'))), 'DisplayName', labels{i});
- end
- hold off;
- set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
- xlabel('Frequency [Hz]');
- ylabel('Compliance');
- legend('location', 'northwest');
+end
+hold off;
+set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
+xlabel('Frequency [Hz]');
+ylabel('Compliance');
+legend('location', 'northwest');
#+end_src
-#+header: :tangle no :exports results :results none :noweb yes
-#+begin_src matlab :var filepath="figs/compliance_micro_station.pdf" :var figsize="wide-tall" :post pdf2svg(file=*this*, ext="png")
- <>
-#+end_src
-
-#+name: fig:compliance_micro_station
-#+caption: Obtained compliance of the Micro-Station ([[./figs/compliance_micro_station.png][png]], [[./figs/compliance_micro_station.pdf][pdf]])
-[[file:figs/compliance_micro_station.png]]
+- [ ] Comparison with the estimated (or measured) compliance
** Conclusion
-#+begin_important
- For such a complex system, we believe that the Simscape Model represents the dynamics of the system with enough fidelity.
-#+end_important
+For such a complex system, we believe that the Simscape Model represents the dynamics of the system with enough fidelity.
+
* Measurement of Positioning Errors
:PROPERTIES:
:HEADER-ARGS:matlab+: :tangle matlab/ustation_2_kinematics.m
@@ -1013,8 +1249,7 @@ end
:END:
#+begin_src matlab
arguments
- args.type char {mustBeMember(args.type,{'rigid', 'flexible', 'none', 'modal-analysis', 'init'})} = 'flexible'
- args.Foffset logical {mustBeNumericOrLogical} = false
+ args.type char {mustBeMember(args.type,{'rigid', 'flexible', 'none', 'modal-analysis'})} = 'flexible'
args.density (1,1) double {mustBeNumeric, mustBeNonnegative} = 2800 % Density [kg/m3]
args.K (3,1) double {mustBeNumeric, mustBeNonnegative} = [4e9; 3e8; 8e8] % [N/m]
args.C (3,1) double {mustBeNumeric, mustBeNonnegative} = [4.0e5; 1.1e5; 9.0e5] % [N/(m/s)]
@@ -1048,8 +1283,6 @@ First, we initialize the =granite= structure.
granite.type = 2;
case 'modal-analysis'
granite.type = 3;
- case 'init'
- granite.type = 4;
end
#+end_src
@@ -1079,20 +1312,6 @@ Z-offset for the initial position of the sample with respect to the granite top
granite.C = args.C; % [N/(m/s)]
#+end_src
-*** Equilibrium position of the each joint.
-:PROPERTIES:
-:UNNUMBERED: t
-:END:
-
-#+begin_src matlab
- if args.Foffset && ~strcmp(args.type, 'none') && ~strcmp(args.type, 'rigid') && ~strcmp(args.type, 'init')
- load('Foffset.mat', 'Fgm');
- granite.Deq = -Fgm'./granite.K;
- else
- granite.Deq = zeros(6,1);
- end
-#+end_src
-
*** Save the Structure
#+begin_src matlab
if exist('./mat', 'dir')
@@ -1130,8 +1349,7 @@ end
:END:
#+begin_src matlab
arguments
- args.type char {mustBeMember(args.type,{'none', 'rigid', 'flexible', 'modal-analysis', 'init'})} = 'flexible'
- args.Foffset logical {mustBeNumericOrLogical} = false
+ args.type char {mustBeMember(args.type,{'none', 'rigid', 'flexible', 'modal-analysis'})} = 'flexible'
end
#+end_src
@@ -1158,8 +1376,6 @@ First, we initialize the =ty= structure.
ty.type = 2;
case 'modal-analysis'
ty.type = 3;
- case 'init'
- ty.type = 4;
end
#+end_src
@@ -1216,20 +1432,6 @@ Define the density of the materials as well as the geometry (STEP files).
ty.C = [8e4; 5e4; 8e4; 2e4; 3e4; 2e4]; % [N/(m/s), N*m/(rad/s)]
#+end_src
-*** Equilibrium position of the each joint.
-:PROPERTIES:
-:UNNUMBERED: t
-:END:
-
-#+begin_src matlab
- if args.Foffset && ~strcmp(args.type, 'none') && ~strcmp(args.type, 'rigid') && ~strcmp(args.type, 'init')
- load('Foffset.mat', 'Ftym');
- ty.Deq = -Ftym'./ty.K;
- else
- ty.Deq = zeros(6,1);
- end
-#+end_src
-
*** Save the Structure
#+begin_src matlab
if exist('./mat', 'dir')
@@ -1267,8 +1469,7 @@ end
:END:
#+begin_src matlab
arguments
- args.type char {mustBeMember(args.type,{'none', 'rigid', 'flexible', 'modal-analysis', 'init'})} = 'flexible'
- args.Foffset logical {mustBeNumericOrLogical} = false
+ args.type char {mustBeMember(args.type,{'none', 'rigid', 'flexible', 'modal-analysis'})} = 'flexible'
args.Ry_init (1,1) double {mustBeNumeric} = 0
end
#+end_src
@@ -1297,8 +1498,6 @@ First, we initialize the =ry= structure.
ry.type = 2;
case 'modal-analysis'
ry.type = 3;
- case 'init'
- ry.type = 4;
end
#+end_src
@@ -1344,20 +1543,6 @@ Z-Offset so that the center of rotation matches the sample center;
ry.C = [1e5; 1e5; 1e5; 3e4; 1e3; 3e4];
#+end_src
-*** Equilibrium position of the each joint.
-:PROPERTIES:
-:UNNUMBERED: t
-:END:
-
-#+begin_src matlab
- if args.Foffset && ~strcmp(args.type, 'none') && ~strcmp(args.type, 'rigid') && ~strcmp(args.type, 'init')
- load('Foffset.mat', 'Fym');
- ry.Deq = -Fym'./ry.K;
- else
- ry.Deq = zeros(6,1);
- end
-#+end_src
-
*** Save the Structure
#+begin_src matlab
if exist('./mat', 'dir')
@@ -1395,8 +1580,7 @@ end
:END:
#+begin_src matlab
arguments
- args.type char {mustBeMember(args.type,{'none', 'rigid', 'flexible', 'modal-analysis', 'init'})} = 'flexible'
- args.Foffset logical {mustBeNumericOrLogical} = false
+ args.type char {mustBeMember(args.type,{'none', 'rigid', 'flexible', 'modal-analysis'})} = 'flexible'
end
#+end_src
@@ -1423,8 +1607,6 @@ First, we initialize the =rz= structure.
rz.type = 2;
case 'modal-analysis'
rz.type = 3;
- case 'init'
- rz.type = 4;
end
#+end_src
@@ -1458,20 +1640,6 @@ Properties of the Material and link to the geometry of the spindle.
rz.C = [4e4; 4e4; 7e4; 1e4; 1e4; 1e4];
#+end_src
-*** Equilibrium position of the each joint.
-:PROPERTIES:
-:UNNUMBERED: t
-:END:
-
-#+begin_src matlab
- if args.Foffset && ~strcmp(args.type, 'none') && ~strcmp(args.type, 'rigid') && ~strcmp(args.type, 'init')
- load('Foffset.mat', 'Fzm');
- rz.Deq = -Fzm'./rz.K;
- else
- rz.Deq = zeros(6,1);
- end
-#+end_src
-
*** Save the Structure
#+begin_src matlab
if exist('./mat', 'dir')
@@ -1509,7 +1677,7 @@ end
:END:
#+begin_src matlab
arguments
- args.type char {mustBeMember(args.type,{'none', 'rigid', 'flexible', 'modal-analysis', 'init', 'compliance'})} = 'flexible'
+ args.type char {mustBeMember(args.type,{'none', 'rigid', 'flexible', 'modal-analysis', 'compliance'})} = 'flexible'
% initializeFramesPositions
args.H (1,1) double {mustBeNumeric, mustBePositive} = 350e-3
args.MO_B (1,1) double {mustBeNumeric} = 270e-3
@@ -1540,8 +1708,6 @@ end
% inverseKinematics
args.AP (3,1) double {mustBeNumeric} = zeros(3,1)
args.ARB (3,3) double {mustBeNumeric} = eye(3)
- % Force that stiffness of each joint should apply at t=0
- args.Foffset logical {mustBeNumericOrLogical} = false
end
#+end_src
@@ -1605,16 +1771,6 @@ end
stewart = initializeInertialSensor(stewart, 'type', 'none');
#+end_src
-Equilibrium position of the each joint.
-#+begin_src matlab
- if args.Foffset && ~strcmp(args.type, 'none') && ~strcmp(args.type, 'rigid') && ~strcmp(args.type, 'init')
- load('Foffset.mat', 'Fhm');
- stewart.actuators.dLeq = -Fhm'./args.Ki;
- else
- stewart.actuators.dLeq = zeros(6,1);
- end
-#+end_src
-
*** Add Type
:PROPERTIES:
:UNNUMBERED: t
@@ -1629,8 +1785,6 @@ Equilibrium position of the each joint.
stewart.type = 2;
case 'modal-analysis'
stewart.type = 3;
- case 'init'
- stewart.type = 4;
case 'compliance'
stewart.type = 5;
end
@@ -1889,73 +2043,19 @@ end
Dhl = struct('time', t, 'signals', struct('values', Dhl));
#+end_src
-*** Axis Compensation
-:PROPERTIES:
-:UNNUMBERED: t
-:END:
-#+begin_src matlab
- %% Axis Compensation - Rm
- t = [0, Ts];
-
- Rm = [args.Rm_pos, args.Rm_pos];
- Rm = struct('time', t, 'signals', struct('values', Rm));
-#+end_src
-
-*** Nano Hexapod
-:PROPERTIES:
-:UNNUMBERED: t
-:END:
-#+begin_src matlab
- %% Nano-Hexapod
- t = [0, Ts];
- Dn = zeros(length(t), 6);
-
- switch args.Dn_type
- case 'constant'
- Dn = [args.Dn_pos, args.Dn_pos];
-
- load('nass_stages.mat', 'nano_hexapod');
-
- AP = [args.Dn_pos(1) ; args.Dn_pos(2) ; args.Dn_pos(3)];
-
- tx = args.Dn_pos(4);
- ty = args.Dn_pos(5);
- tz = args.Dn_pos(6);
-
- ARB = [cos(tz) -sin(tz) 0;
- sin(tz) cos(tz) 0;
- 0 0 1]*...
- [ cos(ty) 0 sin(ty);
- 0 1 0;
- -sin(ty) 0 cos(ty)]*...
- [1 0 0;
- 0 cos(tx) -sin(tx);
- 0 sin(tx) cos(tx)];
-
- [~, Dnl] = inverseKinematics(nano_hexapod, 'AP', AP, 'ARB', ARB);
- Dnl = [Dnl, Dnl];
- otherwise
- warning('Dn_type is not set correctly');
- end
-
- Dn = struct('time', t, 'signals', struct('values', Dn));
- Dnl = struct('time', t, 'signals', struct('values', Dnl));
-#+end_src
-
*** Save the Structure
#+begin_src matlab
-micro_hexapod = stewart;
if exist('./mat', 'dir')
if exist('./mat/nass_references.mat', 'file')
- save('mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'Rm', 'Dn', 'Dnl', 'args', 'Ts', '-append');
+ save('mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'args', 'Ts', '-append');
else
- save('mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'Rm', 'Dn', 'Dnl', 'args', 'Ts');
+ save('mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'args', 'Ts');
end
elseif exist('./matlab', 'dir')
if exist('./matlab/mat/nass_references.mat', 'file')
- save('matlab/mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'Rm', 'Dn', 'Dnl', 'args', 'Ts', '-append');
+ save('matlab/mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'args', 'Ts', '-append');
else
- save('matlab/mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'Rm', 'Dn', 'Dnl', 'args', 'Ts');
+ save('matlab/mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'args', 'Ts');
end
end
#+end_src
@@ -2012,7 +2112,7 @@ end
:UNNUMBERED: t
:END:
#+begin_src matlab
- load('./mat/dist_psd.mat', 'dist_f');
+ load('dist_psd.mat', 'dist_f');
#+end_src
We remove the first frequency point that usually is very large.
@@ -2176,7 +2276,6 @@ We define some parameters that will be used in the algorithm.
*** Save the Structure
#+begin_src matlab
-micro_hexapod = stewart;
if exist('./mat', 'dir')
if exist('./mat/nass_disturbances.mat', 'file')
save('mat/nass_disturbances.mat', 'Dwx', 'Dwy', 'Dwz', 'Fty_x', 'Fty_z', 'Frz_z', 'Fd', 'Ts', 't', 'args', '-append');
@@ -2192,87 +2291,1543 @@ elseif exist('./matlab', 'dir')
end
#+end_src
-** Z-Axis Geophone
+** =initializeStewartPlatform=: Initialize the Stewart Platform structure
:PROPERTIES:
-:header-args:matlab+: :tangle matlab/src/initializeZAxisGeophone.m
+:header-args:matlab+: :tangle matlab/src/initializeStewartPlatform.m
+:header-args:matlab+: :comments none :mkdirp yes :eval no
+:END:
+
+*** Documentation
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+
+#+name: fig:stewart-frames-position
+#+caption: Definition of the position of the frames
+[[file:figs/stewart-frames-position.png]]
+
+*** Function description
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ function [stewart] = initializeStewartPlatform()
+ % initializeStewartPlatform - Initialize the stewart structure
+ %
+ % Syntax: [stewart] = initializeStewartPlatform(args)
+ %
+ % Outputs:
+ % - stewart - A structure with the following sub-structures:
+ % - platform_F -
+ % - platform_M -
+ % - joints_F -
+ % - joints_M -
+ % - struts_F -
+ % - struts_M -
+ % - actuators -
+ % - geometry -
+ % - properties -
+#+end_src
+
+*** Initialize the Stewart structure
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ stewart = struct();
+ stewart.platform_F = struct();
+ stewart.platform_M = struct();
+ stewart.joints_F = struct();
+ stewart.joints_M = struct();
+ stewart.struts_F = struct();
+ stewart.struts_M = struct();
+ stewart.actuators = struct();
+ stewart.sensors = struct();
+ stewart.sensors.inertial = struct();
+ stewart.sensors.force = struct();
+ stewart.sensors.relative = struct();
+ stewart.geometry = struct();
+ stewart.kinematics = struct();
+#+end_src
+
+** =initializeFramesPositions=: Initialize the positions of frames {A}, {B}, {F} and {M}
+:PROPERTIES:
+:header-args:matlab+: :tangle matlab/src/initializeFramesPositions.m
+:header-args:matlab+: :comments none :mkdirp yes :eval no
+:END:
+
+*** Documentation
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+
+#+name: fig:stewart-frames-position
+#+caption: Definition of the position of the frames
+[[file:figs/stewart-frames-position.png]]
+
+*** Function description
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ function [stewart] = initializeFramesPositions(stewart, args)
+ % initializeFramesPositions - Initialize the positions of frames {A}, {B}, {F} and {M}
+ %
+ % Syntax: [stewart] = initializeFramesPositions(stewart, args)
+ %
+ % Inputs:
+ % - args - Can have the following fields:
+ % - H [1x1] - Total Height of the Stewart Platform (height from {F} to {M}) [m]
+ % - MO_B [1x1] - Height of the frame {B} with respect to {M} [m]
+ %
+ % Outputs:
+ % - stewart - A structure with the following fields:
+ % - geometry.H [1x1] - Total Height of the Stewart Platform [m]
+ % - geometry.FO_M [3x1] - Position of {M} with respect to {F} [m]
+ % - platform_M.MO_B [3x1] - Position of {B} with respect to {M} [m]
+ % - platform_F.FO_A [3x1] - Position of {A} with respect to {F} [m]
+#+end_src
+
+*** Optional Parameters
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ arguments
+ stewart
+ args.H (1,1) double {mustBeNumeric, mustBePositive} = 90e-3
+ args.MO_B (1,1) double {mustBeNumeric} = 50e-3
+ end
+#+end_src
+
+*** Compute the position of each frame
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ H = args.H; % Total Height of the Stewart Platform [m]
+
+ FO_M = [0; 0; H]; % Position of {M} with respect to {F} [m]
+
+ MO_B = [0; 0; args.MO_B]; % Position of {B} with respect to {M} [m]
+
+ FO_A = MO_B + FO_M; % Position of {A} with respect to {F} [m]
+#+end_src
+
+*** Populate the =stewart= structure
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ stewart.geometry.H = H;
+ stewart.geometry.FO_M = FO_M;
+ stewart.platform_M.MO_B = MO_B;
+ stewart.platform_F.FO_A = FO_A;
+#+end_src
+
+** =generateGeneralConfiguration=: Generate a Very General Configuration
+:PROPERTIES:
+:header-args:matlab+: :tangle matlab/src/generateGeneralConfiguration.m
+:header-args:matlab+: :comments none :mkdirp yes :eval no
+:END:
+
+*** Documentation
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+Joints are positions on a circle centered with the Z axis of {F} and {M} and at a chosen distance from {F} and {M}.
+The radius of the circles can be chosen as well as the angles where the joints are located (see Figure [[fig:joint_position_general]]).
+
+#+begin_src latex :file stewart_bottom_plate.pdf :tangle no
+ \begin{tikzpicture}
+ % Internal and external limit
+ \draw[fill=white!80!black] (0, 0) circle [radius=3];
+ % Circle where the joints are located
+ \draw[dashed] (0, 0) circle [radius=2.5];
+
+ % Bullets for the positions of the joints
+ \node[] (J1) at ( 80:2.5){$\bullet$};
+ \node[] (J2) at (100:2.5){$\bullet$};
+ \node[] (J3) at (200:2.5){$\bullet$};
+ \node[] (J4) at (220:2.5){$\bullet$};
+ \node[] (J5) at (320:2.5){$\bullet$};
+ \node[] (J6) at (340:2.5){$\bullet$};
+
+ % Name of the points
+ \node[above right] at (J1) {$a_{1}$};
+ \node[above left] at (J2) {$a_{2}$};
+ \node[above left] at (J3) {$a_{3}$};
+ \node[right ] at (J4) {$a_{4}$};
+ \node[left ] at (J5) {$a_{5}$};
+ \node[above right] at (J6) {$a_{6}$};
+
+ % First 2 angles
+ \draw[dashed, ->] (0:1) arc [start angle=0, end angle=80, radius=1] node[below right]{$\theta_{1}$};
+ \draw[dashed, ->] (0:1.5) arc [start angle=0, end angle=100, radius=1.5] node[left ]{$\theta_{2}$};
+
+ % Division of 360 degrees by 3
+ \draw[dashed] (0, 0) -- ( 80:3.2);
+ \draw[dashed] (0, 0) -- (100:3.2);
+ \draw[dashed] (0, 0) -- (200:3.2);
+ \draw[dashed] (0, 0) -- (220:3.2);
+ \draw[dashed] (0, 0) -- (320:3.2);
+ \draw[dashed] (0, 0) -- (340:3.2);
+
+ % Radius for the position of the joints
+ \draw[<->] (0, 0) --node[near end, above]{$R$} (180:2.5);
+
+ \draw[->] (0, 0) -- ++(3.4, 0) node[above]{$x$};
+ \draw[->] (0, 0) -- ++(0, 3.4) node[left]{$y$};
+ \end{tikzpicture}
+#+end_src
+
+#+name: fig:joint_position_general
+#+caption: Position of the joints
+#+RESULTS:
+[[file:figs/stewart_bottom_plate.png]]
+
+*** Function description
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ function [stewart] = generateGeneralConfiguration(stewart, args)
+ % generateGeneralConfiguration - Generate a Very General Configuration
+ %
+ % Syntax: [stewart] = generateGeneralConfiguration(stewart, args)
+ %
+ % Inputs:
+ % - args - Can have the following fields:
+ % - FH [1x1] - Height of the position of the fixed joints with respect to the frame {F} [m]
+ % - FR [1x1] - Radius of the position of the fixed joints in the X-Y [m]
+ % - FTh [6x1] - Angles of the fixed joints in the X-Y plane with respect to the X axis [rad]
+ % - MH [1x1] - Height of the position of the mobile joints with respect to the frame {M} [m]
+ % - FR [1x1] - Radius of the position of the mobile joints in the X-Y [m]
+ % - MTh [6x1] - Angles of the mobile joints in the X-Y plane with respect to the X axis [rad]
+ %
+ % Outputs:
+ % - stewart - updated Stewart structure with the added fields:
+ % - platform_F.Fa [3x6] - Its i'th column is the position vector of joint ai with respect to {F}
+ % - platform_M.Mb [3x6] - Its i'th column is the position vector of joint bi with respect to {M}
+#+end_src
+
+*** Optional Parameters
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ arguments
+ stewart
+ args.FH (1,1) double {mustBeNumeric, mustBePositive} = 15e-3
+ args.FR (1,1) double {mustBeNumeric, mustBePositive} = 115e-3;
+ args.FTh (6,1) double {mustBeNumeric} = [-10, 10, 120-10, 120+10, 240-10, 240+10]*(pi/180);
+ args.MH (1,1) double {mustBeNumeric, mustBePositive} = 15e-3
+ args.MR (1,1) double {mustBeNumeric, mustBePositive} = 90e-3;
+ args.MTh (6,1) double {mustBeNumeric} = [-60+10, 60-10, 60+10, 180-10, 180+10, -60-10]*(pi/180);
+ end
+#+end_src
+
+*** Compute the pose
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ Fa = zeros(3,6);
+ Mb = zeros(3,6);
+#+end_src
+
+#+begin_src matlab
+ for i = 1:6
+ Fa(:,i) = [args.FR*cos(args.FTh(i)); args.FR*sin(args.FTh(i)); args.FH];
+ Mb(:,i) = [args.MR*cos(args.MTh(i)); args.MR*sin(args.MTh(i)); -args.MH];
+ end
+#+end_src
+
+*** Populate the =stewart= structure
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ stewart.platform_F.Fa = Fa;
+ stewart.platform_M.Mb = Mb;
+#+end_src
+
+** =computeJointsPose=: Compute the Pose of the Joints
+:PROPERTIES:
+:header-args:matlab+: :tangle matlab/src/computeJointsPose.m
+:header-args:matlab+: :comments none :mkdirp yes :eval no
+:END:
+
+*** Documentation
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+
+#+name: fig:stewart-struts
+#+caption: Position and orientation of the struts
+[[file:figs/stewart-struts.png]]
+
+*** Function description
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ function [stewart] = computeJointsPose(stewart)
+ % computeJointsPose -
+ %
+ % Syntax: [stewart] = computeJointsPose(stewart)
+ %
+ % Inputs:
+ % - stewart - A structure with the following fields
+ % - platform_F.Fa [3x6] - Its i'th column is the position vector of joint ai with respect to {F}
+ % - platform_M.Mb [3x6] - Its i'th column is the position vector of joint bi with respect to {M}
+ % - platform_F.FO_A [3x1] - Position of {A} with respect to {F}
+ % - platform_M.MO_B [3x1] - Position of {B} with respect to {M}
+ % - geometry.FO_M [3x1] - Position of {M} with respect to {F}
+ %
+ % Outputs:
+ % - stewart - A structure with the following added fields
+ % - geometry.Aa [3x6] - The i'th column is the position of ai with respect to {A}
+ % - geometry.Ab [3x6] - The i'th column is the position of bi with respect to {A}
+ % - geometry.Ba [3x6] - The i'th column is the position of ai with respect to {B}
+ % - geometry.Bb [3x6] - The i'th column is the position of bi with respect to {B}
+ % - geometry.l [6x1] - The i'th element is the initial length of strut i
+ % - geometry.As [3x6] - The i'th column is the unit vector of strut i expressed in {A}
+ % - geometry.Bs [3x6] - The i'th column is the unit vector of strut i expressed in {B}
+ % - struts_F.l [6x1] - Length of the Fixed part of the i'th strut
+ % - struts_M.l [6x1] - Length of the Mobile part of the i'th strut
+ % - platform_F.FRa [3x3x6] - The i'th 3x3 array is the rotation matrix to orientate the bottom of the i'th strut from {F}
+ % - platform_M.MRb [3x3x6] - The i'th 3x3 array is the rotation matrix to orientate the top of the i'th strut from {M}
+#+end_src
+
+*** Check the =stewart= structure elements
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ assert(isfield(stewart.platform_F, 'Fa'), 'stewart.platform_F should have attribute Fa')
+ Fa = stewart.platform_F.Fa;
+
+ assert(isfield(stewart.platform_M, 'Mb'), 'stewart.platform_M should have attribute Mb')
+ Mb = stewart.platform_M.Mb;
+
+ assert(isfield(stewart.platform_F, 'FO_A'), 'stewart.platform_F should have attribute FO_A')
+ FO_A = stewart.platform_F.FO_A;
+
+ assert(isfield(stewart.platform_M, 'MO_B'), 'stewart.platform_M should have attribute MO_B')
+ MO_B = stewart.platform_M.MO_B;
+
+ assert(isfield(stewart.geometry, 'FO_M'), 'stewart.geometry should have attribute FO_M')
+ FO_M = stewart.geometry.FO_M;
+#+end_src
+
+*** Compute the position of the Joints
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ Aa = Fa - repmat(FO_A, [1, 6]);
+ Bb = Mb - repmat(MO_B, [1, 6]);
+
+ Ab = Bb - repmat(-MO_B-FO_M+FO_A, [1, 6]);
+ Ba = Aa - repmat( MO_B+FO_M-FO_A, [1, 6]);
+#+end_src
+
+*** Compute the strut length and orientation
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ As = (Ab - Aa)./vecnorm(Ab - Aa); % As_i is the i'th vector of As
+
+ l = vecnorm(Ab - Aa)';
+#+end_src
+
+#+begin_src matlab
+ Bs = (Bb - Ba)./vecnorm(Bb - Ba);
+#+end_src
+
+*** Compute the orientation of the Joints
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ FRa = zeros(3,3,6);
+ MRb = zeros(3,3,6);
+
+ for i = 1:6
+ FRa(:,:,i) = [cross([0;1;0], As(:,i)) , cross(As(:,i), cross([0;1;0], As(:,i))) , As(:,i)];
+ FRa(:,:,i) = FRa(:,:,i)./vecnorm(FRa(:,:,i));
+
+ MRb(:,:,i) = [cross([0;1;0], Bs(:,i)) , cross(Bs(:,i), cross([0;1;0], Bs(:,i))) , Bs(:,i)];
+ MRb(:,:,i) = MRb(:,:,i)./vecnorm(MRb(:,:,i));
+ end
+#+end_src
+
+*** Populate the =stewart= structure
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ stewart.geometry.Aa = Aa;
+ stewart.geometry.Ab = Ab;
+ stewart.geometry.Ba = Ba;
+ stewart.geometry.Bb = Bb;
+ stewart.geometry.As = As;
+ stewart.geometry.Bs = Bs;
+ stewart.geometry.l = l;
+
+ stewart.struts_F.l = l/2;
+ stewart.struts_M.l = l/2;
+
+ stewart.platform_F.FRa = FRa;
+ stewart.platform_M.MRb = MRb;
+#+end_src
+
+** =initializeCylindricalPlatforms=: Initialize the geometry of the Fixed and Mobile Platforms
+:PROPERTIES:
+:header-args:matlab+: :tangle matlab/src/initializeCylindricalPlatforms.m
+:header-args:matlab+: :comments none :mkdirp yes :eval no
+:END:
+
+*** Function description
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ function [stewart] = initializeCylindricalPlatforms(stewart, args)
+ % initializeCylindricalPlatforms - Initialize the geometry of the Fixed and Mobile Platforms
+ %
+ % Syntax: [stewart] = initializeCylindricalPlatforms(args)
+ %
+ % Inputs:
+ % - args - Structure with the following fields:
+ % - Fpm [1x1] - Fixed Platform Mass [kg]
+ % - Fph [1x1] - Fixed Platform Height [m]
+ % - Fpr [1x1] - Fixed Platform Radius [m]
+ % - Mpm [1x1] - Mobile Platform Mass [kg]
+ % - Mph [1x1] - Mobile Platform Height [m]
+ % - Mpr [1x1] - Mobile Platform Radius [m]
+ %
+ % Outputs:
+ % - stewart - updated Stewart structure with the added fields:
+ % - platform_F [struct] - structure with the following fields:
+ % - type = 1
+ % - M [1x1] - Fixed Platform Mass [kg]
+ % - I [3x3] - Fixed Platform Inertia matrix [kg*m^2]
+ % - H [1x1] - Fixed Platform Height [m]
+ % - R [1x1] - Fixed Platform Radius [m]
+ % - platform_M [struct] - structure with the following fields:
+ % - M [1x1] - Mobile Platform Mass [kg]
+ % - I [3x3] - Mobile Platform Inertia matrix [kg*m^2]
+ % - H [1x1] - Mobile Platform Height [m]
+ % - R [1x1] - Mobile Platform Radius [m]
+#+end_src
+
+*** Optional Parameters
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ arguments
+ stewart
+ args.Fpm (1,1) double {mustBeNumeric, mustBePositive} = 1
+ args.Fph (1,1) double {mustBeNumeric, mustBePositive} = 10e-3
+ args.Fpr (1,1) double {mustBeNumeric, mustBePositive} = 125e-3
+ args.Mpm (1,1) double {mustBeNumeric, mustBePositive} = 1
+ args.Mph (1,1) double {mustBeNumeric, mustBePositive} = 10e-3
+ args.Mpr (1,1) double {mustBeNumeric, mustBePositive} = 100e-3
+ end
+#+end_src
+
+*** Compute the Inertia matrices of platforms
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ I_F = diag([1/12*args.Fpm * (3*args.Fpr^2 + args.Fph^2), ...
+ 1/12*args.Fpm * (3*args.Fpr^2 + args.Fph^2), ...
+ 1/2 *args.Fpm * args.Fpr^2]);
+#+end_src
+
+#+begin_src matlab
+ I_M = diag([1/12*args.Mpm * (3*args.Mpr^2 + args.Mph^2), ...
+ 1/12*args.Mpm * (3*args.Mpr^2 + args.Mph^2), ...
+ 1/2 *args.Mpm * args.Mpr^2]);
+#+end_src
+
+*** Populate the =stewart= structure
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ stewart.platform_F.type = 1;
+
+ stewart.platform_F.I = I_F;
+ stewart.platform_F.M = args.Fpm;
+ stewart.platform_F.R = args.Fpr;
+ stewart.platform_F.H = args.Fph;
+#+end_src
+
+#+begin_src matlab
+ stewart.platform_M.type = 1;
+
+ stewart.platform_M.I = I_M;
+ stewart.platform_M.M = args.Mpm;
+ stewart.platform_M.R = args.Mpr;
+ stewart.platform_M.H = args.Mph;
+#+end_src
+
+** =initializeCylindricalStruts=: Define the inertia of cylindrical struts
+:PROPERTIES:
+:header-args:matlab+: :tangle matlab/src/initializeCylindricalStruts.m
+:header-args:matlab+: :comments none :mkdirp yes :eval no
+:END:
+
+*** Function description
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ function [stewart] = initializeCylindricalStruts(stewart, args)
+ % initializeCylindricalStruts - Define the mass and moment of inertia of cylindrical struts
+ %
+ % Syntax: [stewart] = initializeCylindricalStruts(args)
+ %
+ % Inputs:
+ % - args - Structure with the following fields:
+ % - Fsm [1x1] - Mass of the Fixed part of the struts [kg]
+ % - Fsh [1x1] - Height of cylinder for the Fixed part of the struts [m]
+ % - Fsr [1x1] - Radius of cylinder for the Fixed part of the struts [m]
+ % - Msm [1x1] - Mass of the Mobile part of the struts [kg]
+ % - Msh [1x1] - Height of cylinder for the Mobile part of the struts [m]
+ % - Msr [1x1] - Radius of cylinder for the Mobile part of the struts [m]
+ %
+ % Outputs:
+ % - stewart - updated Stewart structure with the added fields:
+ % - struts_F [struct] - structure with the following fields:
+ % - M [6x1] - Mass of the Fixed part of the struts [kg]
+ % - I [3x3x6] - Moment of Inertia for the Fixed part of the struts [kg*m^2]
+ % - H [6x1] - Height of cylinder for the Fixed part of the struts [m]
+ % - R [6x1] - Radius of cylinder for the Fixed part of the struts [m]
+ % - struts_M [struct] - structure with the following fields:
+ % - M [6x1] - Mass of the Mobile part of the struts [kg]
+ % - I [3x3x6] - Moment of Inertia for the Mobile part of the struts [kg*m^2]
+ % - H [6x1] - Height of cylinder for the Mobile part of the struts [m]
+ % - R [6x1] - Radius of cylinder for the Mobile part of the struts [m]
+#+end_src
+
+*** Optional Parameters
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ arguments
+ stewart
+ args.Fsm (1,1) double {mustBeNumeric, mustBePositive} = 0.1
+ args.Fsh (1,1) double {mustBeNumeric, mustBePositive} = 50e-3
+ args.Fsr (1,1) double {mustBeNumeric, mustBePositive} = 5e-3
+ args.Msm (1,1) double {mustBeNumeric, mustBePositive} = 0.1
+ args.Msh (1,1) double {mustBeNumeric, mustBePositive} = 50e-3
+ args.Msr (1,1) double {mustBeNumeric, mustBePositive} = 5e-3
+ end
+#+end_src
+
+*** Compute the properties of the cylindrical struts
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+
+#+begin_src matlab
+ Fsm = ones(6,1).*args.Fsm;
+ Fsh = ones(6,1).*args.Fsh;
+ Fsr = ones(6,1).*args.Fsr;
+
+ Msm = ones(6,1).*args.Msm;
+ Msh = ones(6,1).*args.Msh;
+ Msr = ones(6,1).*args.Msr;
+#+end_src
+
+#+begin_src matlab
+ I_F = zeros(3, 3, 6); % Inertia of the "fixed" part of the strut
+ I_M = zeros(3, 3, 6); % Inertia of the "mobile" part of the strut
+
+ for i = 1:6
+ I_F(:,:,i) = diag([1/12 * Fsm(i) * (3*Fsr(i)^2 + Fsh(i)^2), ...
+ 1/12 * Fsm(i) * (3*Fsr(i)^2 + Fsh(i)^2), ...
+ 1/2 * Fsm(i) * Fsr(i)^2]);
+
+ I_M(:,:,i) = diag([1/12 * Msm(i) * (3*Msr(i)^2 + Msh(i)^2), ...
+ 1/12 * Msm(i) * (3*Msr(i)^2 + Msh(i)^2), ...
+ 1/2 * Msm(i) * Msr(i)^2]);
+ end
+#+end_src
+
+*** Populate the =stewart= structure
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ stewart.struts_M.type = 1;
+
+ stewart.struts_M.I = I_M;
+ stewart.struts_M.M = Msm;
+ stewart.struts_M.R = Msr;
+ stewart.struts_M.H = Msh;
+#+end_src
+
+#+begin_src matlab
+ stewart.struts_F.type = 1;
+
+ stewart.struts_F.I = I_F;
+ stewart.struts_F.M = Fsm;
+ stewart.struts_F.R = Fsr;
+ stewart.struts_F.H = Fsh;
+#+end_src
+
+** =initializeStrutDynamics=: Add Stiffness and Damping properties of each strut
+:PROPERTIES:
+:header-args:matlab+: :tangle matlab/src/initializeStrutDynamics.m
+:header-args:matlab+: :comments none :mkdirp yes :eval no
+:END:
+
+*** Documentation
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+
+#+name: fig:piezoelectric_stack
+#+attr_html: :width 500px
+#+caption: Example of a piezoelectric stach actuator (PI)
+[[file:figs/piezoelectric_stack.jpg]]
+
+A simplistic model of such amplified actuator is shown in Figure [[fig:actuator_model_simple]] where:
+- $K$ represent the vertical stiffness of the actuator
+- $C$ represent the vertical damping of the actuator
+- $F$ represents the force applied by the actuator
+- $F_{m}$ represents the total measured force
+- $v_{m}$ represents the absolute velocity of the top part of the actuator
+- $d_{m}$ represents the total relative displacement of the actuator
+
+#+begin_src latex :file actuator_model_simple.pdf :tangle no
+ \begin{tikzpicture}
+ \draw (-1, 0) -- (1, 0);
+
+ % Spring, Damper, and Actuator
+ \draw[spring] (-1, 0) -- (-1, 1.5) node[midway, left=0.1]{$K$};
+ \draw[damper] ( 0, 0) -- ( 0, 1.5) node[midway, left=0.2]{$C$};
+ \draw[actuator] ( 1, 0) -- ( 1, 1.5) node[midway, left=0.1](F){$F$};
+
+ \node[forcesensor={2}{0.2}] (fsens) at (0, 1.5){};
+
+ \node[left] at (fsens.west) {$F_{m}$};
+
+ \draw[dashed] (1, 0) -- ++(0.4, 0);
+ \draw[dashed] (1, 1.7) -- ++(0.4, 0);
+
+ \draw[->] (0, 1.7)node[]{$\bullet$} -- ++(0, 0.5) node[right]{$v_{m}$};
+
+ \draw[<->] (1.4, 0) -- ++(0, 1.7) node[midway, right]{$d_{m}$};
+ \end{tikzpicture}
+#+end_src
+
+#+name: fig:actuator_model_simple
+#+caption: Simple model of an Actuator
+#+RESULTS:
+[[file:figs/actuator_model_simple.png]]
+
+*** Function description
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ function [stewart] = initializeStrutDynamics(stewart, args)
+ % initializeStrutDynamics - Add Stiffness and Damping properties of each strut
+ %
+ % Syntax: [stewart] = initializeStrutDynamics(args)
+ %
+ % Inputs:
+ % - args - Structure with the following fields:
+ % - K [6x1] - Stiffness of each strut [N/m]
+ % - C [6x1] - Damping of each strut [N/(m/s)]
+ %
+ % Outputs:
+ % - stewart - updated Stewart structure with the added fields:
+ % - actuators.type = 1
+ % - actuators.K [6x1] - Stiffness of each strut [N/m]
+ % - actuators.C [6x1] - Damping of each strut [N/(m/s)]
+#+end_src
+
+*** Optional Parameters
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ arguments
+ stewart
+ args.type char {mustBeMember(args.type,{'classical', 'amplified'})} = 'classical'
+ args.K (6,1) double {mustBeNumeric, mustBeNonnegative} = 20e6*ones(6,1)
+ args.C (6,1) double {mustBeNumeric, mustBeNonnegative} = 2e1*ones(6,1)
+ args.k1 (6,1) double {mustBeNumeric} = 1e6*ones(6,1)
+ args.ke (6,1) double {mustBeNumeric} = 5e6*ones(6,1)
+ args.ka (6,1) double {mustBeNumeric} = 60e6*ones(6,1)
+ args.c1 (6,1) double {mustBeNumeric} = 10*ones(6,1)
+ args.F_gain (6,1) double {mustBeNumeric} = 1*ones(6,1)
+ args.me (6,1) double {mustBeNumeric} = 0.01*ones(6,1)
+ args.ma (6,1) double {mustBeNumeric} = 0.01*ones(6,1)
+ end
+#+end_src
+
+*** Add Stiffness and Damping properties of each strut
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ if strcmp(args.type, 'classical')
+ stewart.actuators.type = 1;
+ elseif strcmp(args.type, 'amplified')
+ stewart.actuators.type = 2;
+ end
+
+ stewart.actuators.K = args.K;
+ stewart.actuators.C = args.C;
+
+ stewart.actuators.k1 = args.k1;
+ stewart.actuators.c1 = args.c1;
+
+ stewart.actuators.ka = args.ka;
+ stewart.actuators.ke = args.ke;
+
+ stewart.actuators.F_gain = args.F_gain;
+
+ stewart.actuators.ma = args.ma;
+ stewart.actuators.me = args.me;
+#+end_src
+
+** =initializeJointDynamics=: Add Stiffness and Damping properties for spherical joints
+:PROPERTIES:
+:header-args:matlab+: :tangle matlab/src/initializeJointDynamics.m
+:header-args:matlab+: :comments none :mkdirp yes :eval no
+:END:
+
+*** Function description
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ function [stewart] = initializeJointDynamics(stewart, args)
+ % initializeJointDynamics - Add Stiffness and Damping properties for the spherical joints
+ %
+ % Syntax: [stewart] = initializeJointDynamics(args)
+ %
+ % Inputs:
+ % - args - Structure with the following fields:
+ % - type_F - 'universal', 'spherical', 'universal_p', 'spherical_p'
+ % - type_M - 'universal', 'spherical', 'universal_p', 'spherical_p'
+ % - Kf_M [6x1] - Bending (Rx, Ry) Stiffness for each top joints [(N.m)/rad]
+ % - Kt_M [6x1] - Torsion (Rz) Stiffness for each top joints [(N.m)/rad]
+ % - Cf_M [6x1] - Bending (Rx, Ry) Damping of each top joint [(N.m)/(rad/s)]
+ % - Ct_M [6x1] - Torsion (Rz) Damping of each top joint [(N.m)/(rad/s)]
+ % - Kf_F [6x1] - Bending (Rx, Ry) Stiffness for each bottom joints [(N.m)/rad]
+ % - Kt_F [6x1] - Torsion (Rz) Stiffness for each bottom joints [(N.m)/rad]
+ % - Cf_F [6x1] - Bending (Rx, Ry) Damping of each bottom joint [(N.m)/(rad/s)]
+ % - Cf_F [6x1] - Torsion (Rz) Damping of each bottom joint [(N.m)/(rad/s)]
+ %
+ % Outputs:
+ % - stewart - updated Stewart structure with the added fields:
+ % - stewart.joints_F and stewart.joints_M:
+ % - type - 1 (universal), 2 (spherical), 3 (universal perfect), 4 (spherical perfect)
+ % - Kx, Ky, Kz [6x1] - Translation (Tx, Ty, Tz) Stiffness [N/m]
+ % - Kf [6x1] - Flexion (Rx, Ry) Stiffness [(N.m)/rad]
+ % - Kt [6x1] - Torsion (Rz) Stiffness [(N.m)/rad]
+ % - Cx, Cy, Cz [6x1] - Translation (Rx, Ry) Damping [N/(m/s)]
+ % - Cf [6x1] - Flexion (Rx, Ry) Damping [(N.m)/(rad/s)]
+ % - Cb [6x1] - Torsion (Rz) Damping [(N.m)/(rad/s)]
+#+end_src
+
+*** Optional Parameters
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ arguments
+ stewart
+ args.type_F char {mustBeMember(args.type_F,{'universal', 'spherical', 'universal_p', 'spherical_p', 'universal_3dof', 'spherical_3dof', 'flexible'})} = 'universal'
+ args.type_M char {mustBeMember(args.type_M,{'universal', 'spherical', 'universal_p', 'spherical_p', 'universal_3dof', 'spherical_3dof', 'flexible'})} = 'spherical'
+ args.Kf_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 33*ones(6,1)
+ args.Cf_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-4*ones(6,1)
+ args.Kt_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 236*ones(6,1)
+ args.Ct_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-3*ones(6,1)
+ args.Kf_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 33*ones(6,1)
+ args.Cf_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-4*ones(6,1)
+ args.Kt_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 236*ones(6,1)
+ args.Ct_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-3*ones(6,1)
+ args.Ka_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1.2e8*ones(6,1)
+ args.Ca_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e1*ones(6,1)
+ args.Kr_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1.1e7*ones(6,1)
+ args.Cr_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e1*ones(6,1)
+ args.Ka_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1.2e8*ones(6,1)
+ args.Ca_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e1*ones(6,1)
+ args.Kr_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1.1e7*ones(6,1)
+ args.Cr_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e1*ones(6,1)
+ args.K_M double {mustBeNumeric} = zeros(6,6)
+ args.M_M double {mustBeNumeric} = zeros(6,6)
+ args.n_xyz_M double {mustBeNumeric} = zeros(2,3)
+ args.xi_M double {mustBeNumeric} = 0.1
+ args.step_file_M char {} = ''
+ args.K_F double {mustBeNumeric} = zeros(6,6)
+ args.M_F double {mustBeNumeric} = zeros(6,6)
+ args.n_xyz_F double {mustBeNumeric} = zeros(2,3)
+ args.xi_F double {mustBeNumeric} = 0.1
+ args.step_file_F char {} = ''
+ end
+#+end_src
+
+*** Add Actuator Type
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ switch args.type_F
+ case 'universal'
+ stewart.joints_F.type = 1;
+ case 'spherical'
+ stewart.joints_F.type = 2;
+ case 'universal_p'
+ stewart.joints_F.type = 3;
+ case 'spherical_p'
+ stewart.joints_F.type = 4;
+ case 'flexible'
+ stewart.joints_F.type = 5;
+ case 'universal_3dof'
+ stewart.joints_F.type = 6;
+ case 'spherical_3dof'
+ stewart.joints_F.type = 7;
+ end
+
+ switch args.type_M
+ case 'universal'
+ stewart.joints_M.type = 1;
+ case 'spherical'
+ stewart.joints_M.type = 2;
+ case 'universal_p'
+ stewart.joints_M.type = 3;
+ case 'spherical_p'
+ stewart.joints_M.type = 4;
+ case 'flexible'
+ stewart.joints_M.type = 5;
+ case 'universal_3dof'
+ stewart.joints_M.type = 6;
+ case 'spherical_3dof'
+ stewart.joints_M.type = 7;
+ end
+#+end_src
+
+*** Add Stiffness and Damping in Translation of each strut
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+Axial and Radial (shear) Stiffness
+#+begin_src matlab
+ stewart.joints_M.Ka = args.Ka_M;
+ stewart.joints_M.Kr = args.Kr_M;
+
+ stewart.joints_F.Ka = args.Ka_F;
+ stewart.joints_F.Kr = args.Kr_F;
+#+end_src
+
+Translation Damping
+#+begin_src matlab
+ stewart.joints_M.Ca = args.Ca_M;
+ stewart.joints_M.Cr = args.Cr_M;
+
+ stewart.joints_F.Ca = args.Ca_F;
+ stewart.joints_F.Cr = args.Cr_F;
+#+end_src
+
+*** Add Stiffness and Damping in Rotation of each strut
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+Rotational Stiffness
+#+begin_src matlab
+ stewart.joints_M.Kf = args.Kf_M;
+ stewart.joints_M.Kt = args.Kt_M;
+
+ stewart.joints_F.Kf = args.Kf_F;
+ stewart.joints_F.Kt = args.Kt_F;
+#+end_src
+
+Rotational Damping
+#+begin_src matlab
+ stewart.joints_M.Cf = args.Cf_M;
+ stewart.joints_M.Ct = args.Ct_M;
+
+ stewart.joints_F.Cf = args.Cf_F;
+ stewart.joints_F.Ct = args.Ct_F;
+#+end_src
+
+*** Stiffness and Mass matrices for flexible joint
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+
+#+begin_src matlab
+ stewart.joints_F.M = args.M_F;
+ stewart.joints_F.K = args.K_F;
+ stewart.joints_F.n_xyz = args.n_xyz_F;
+ stewart.joints_F.xi = args.xi_F;
+ stewart.joints_F.xi = args.xi_F;
+ stewart.joints_F.step_file = args.step_file_F;
+
+ stewart.joints_M.M = args.M_M;
+ stewart.joints_M.K = args.K_M;
+ stewart.joints_M.n_xyz = args.n_xyz_M;
+ stewart.joints_M.xi = args.xi_M;
+ stewart.joints_M.step_file = args.step_file_M;
+#+end_src
+
+** =initializeStewartPose=: Determine the initial stroke in each leg to have the wanted pose
+:PROPERTIES:
+:header-args:matlab+: :tangle matlab/src/initializeStewartPose.m
+:header-args:matlab+: :comments none :mkdirp yes :eval no
+:END:
+
+*** Function description
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ function [stewart] = initializeStewartPose(stewart, args)
+ % initializeStewartPose - Determine the initial stroke in each leg to have the wanted pose
+ % It uses the inverse kinematic
+ %
+ % Syntax: [stewart] = initializeStewartPose(stewart, args)
+ %
+ % Inputs:
+ % - stewart - A structure with the following fields
+ % - Aa [3x6] - The positions ai expressed in {A}
+ % - Bb [3x6] - The positions bi expressed in {B}
+ % - args - Can have the following fields:
+ % - AP [3x1] - The wanted position of {B} with respect to {A}
+ % - ARB [3x3] - The rotation matrix that gives the wanted orientation of {B} with respect to {A}
+ %
+ % Outputs:
+ % - stewart - updated Stewart structure with the added fields:
+ % - actuators.Leq [6x1] - The 6 needed displacement of the struts from the initial position in [m] to have the wanted pose of {B} w.r.t. {A}
+#+end_src
+
+*** Optional Parameters
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ arguments
+ stewart
+ args.AP (3,1) double {mustBeNumeric} = zeros(3,1)
+ args.ARB (3,3) double {mustBeNumeric} = eye(3)
+ end
+#+end_src
+
+*** Use the Inverse Kinematic function
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ [Li, dLi] = inverseKinematics(stewart, 'AP', args.AP, 'ARB', args.ARB);
+#+end_src
+
+*** Populate the =stewart= structure
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ stewart.actuators.Leq = dLi;
+#+end_src
+
+** =computeJacobian=: Compute the Jacobian Matrix
+:PROPERTIES:
+:header-args:matlab+: :tangle matlab/src/computeJacobian.m
+:header-args:matlab+: :comments none :mkdirp yes :eval no
+:END:
+
+*** Function description
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ function [stewart] = computeJacobian(stewart)
+ % computeJacobian -
+ %
+ % Syntax: [stewart] = computeJacobian(stewart)
+ %
+ % Inputs:
+ % - stewart - With at least the following fields:
+ % - geometry.As [3x6] - The 6 unit vectors for each strut expressed in {A}
+ % - geometry.Ab [3x6] - The 6 position of the joints bi expressed in {A}
+ % - actuators.K [6x1] - Total stiffness of the actuators
+ %
+ % Outputs:
+ % - stewart - With the 3 added field:
+ % - kinematics.J [6x6] - The Jacobian Matrix
+ % - kinematics.K [6x6] - The Stiffness Matrix
+ % - kinematics.C [6x6] - The Compliance Matrix
+#+end_src
+
+*** Check the =stewart= structure elements
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ assert(isfield(stewart.geometry, 'As'), 'stewart.geometry should have attribute As')
+ As = stewart.geometry.As;
+
+ assert(isfield(stewart.geometry, 'Ab'), 'stewart.geometry should have attribute Ab')
+ Ab = stewart.geometry.Ab;
+
+ assert(isfield(stewart.actuators, 'K'), 'stewart.actuators should have attribute K')
+ Ki = stewart.actuators.K;
+#+end_src
+
+
+*** Compute Jacobian Matrix
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ J = [As' , cross(Ab, As)'];
+#+end_src
+
+*** Compute Stiffness Matrix
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ K = J'*diag(Ki)*J;
+#+end_src
+
+*** Compute Compliance Matrix
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ C = inv(K);
+#+end_src
+
+*** Populate the =stewart= structure
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ stewart.kinematics.J = J;
+ stewart.kinematics.K = K;
+ stewart.kinematics.C = C;
+#+end_src
+
+** =initializeInertialSensor=: Initialize the inertial sensor in each strut
+:PROPERTIES:
+:header-args:matlab+: :tangle matlab/src/initializeInertialSensor.m
+:header-args:matlab+: :comments none :mkdirp yes :eval no
+:END:
+
+*** Geophone - Working Principle
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+From the schematic of the Z-axis geophone shown in Figure [[fig:z_axis_geophone]], we can write the transfer function from the support velocity $\dot{w}$ to the relative velocity of the inertial mass $\dot{d}$:
+\[ \frac{\dot{d}}{\dot{w}} = \frac{-\frac{s^2}{{\omega_0}^2}}{\frac{s^2}{{\omega_0}^2} + 2 \xi \frac{s}{\omega_0} + 1} \]
+with:
+- $\omega_0 = \sqrt{\frac{k}{m}}$
+- $\xi = \frac{1}{2} \sqrt{\frac{m}{k}}$
+
+#+name: fig:z_axis_geophone
+#+caption: Schematic of a Z-Axis geophone
+[[file:figs/inertial_sensor.png]]
+
+We see that at frequencies above $\omega_0$:
+\[ \frac{\dot{d}}{\dot{w}} \approx -1 \]
+
+And thus, the measurement of the relative velocity of the mass with respect to its support gives the absolute velocity of the support.
+
+We generally want to have the smallest resonant frequency $\omega_0$ to measure low frequency absolute velocity, however there is a trade-off between $\omega_0$ and the mass of the inertial mass.
+
+*** Accelerometer - Working Principle
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+From the schematic of the Z-axis accelerometer shown in Figure [[fig:z_axis_accelerometer]], we can write the transfer function from the support acceleration $\ddot{w}$ to the relative position of the inertial mass $d$:
+\[ \frac{d}{\ddot{w}} = \frac{-\frac{1}{{\omega_0}^2}}{\frac{s^2}{{\omega_0}^2} + 2 \xi \frac{s}{\omega_0} + 1} \]
+with:
+- $\omega_0 = \sqrt{\frac{k}{m}}$
+- $\xi = \frac{1}{2} \sqrt{\frac{m}{k}}$
+
+#+name: fig:z_axis_accelerometer
+#+caption: Schematic of a Z-Axis geophone
+[[file:figs/inertial_sensor.png]]
+
+We see that at frequencies below $\omega_0$:
+\[ \frac{d}{\ddot{w}} \approx -\frac{1}{{\omega_0}^2} \]
+
+And thus, the measurement of the relative displacement of the mass with respect to its support gives the absolute acceleration of the support.
+
+Note that there is trade-off between:
+- the highest measurable acceleration $\omega_0$
+- the sensitivity of the accelerometer which is equal to $-\frac{1}{{\omega_0}^2}$
+
+*** Function description
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ function [stewart] = initializeInertialSensor(stewart, args)
+ % initializeInertialSensor - Initialize the inertial sensor in each strut
+ %
+ % Syntax: [stewart] = initializeInertialSensor(args)
+ %
+ % Inputs:
+ % - args - Structure with the following fields:
+ % - type - 'geophone', 'accelerometer', 'none'
+ % - mass [1x1] - Weight of the inertial mass [kg]
+ % - freq [1x1] - Cutoff frequency [Hz]
+ %
+ % Outputs:
+ % - stewart - updated Stewart structure with the added fields:
+ % - stewart.sensors.inertial
+ % - type - 1 (geophone), 2 (accelerometer), 3 (none)
+ % - K [1x1] - Stiffness [N/m]
+ % - C [1x1] - Damping [N/(m/s)]
+ % - M [1x1] - Inertial Mass [kg]
+ % - G [1x1] - Gain
+#+end_src
+
+*** Optional Parameters
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ arguments
+ stewart
+ args.type char {mustBeMember(args.type,{'geophone', 'accelerometer', 'none'})} = 'none'
+ args.mass (1,1) double {mustBeNumeric, mustBeNonnegative} = 1e-2
+ args.freq (1,1) double {mustBeNumeric, mustBeNonnegative} = 1e3
+ end
+#+end_src
+
+*** Compute the properties of the sensor
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ sensor = struct();
+
+ switch args.type
+ case 'geophone'
+ sensor.type = 1;
+
+ sensor.M = args.mass;
+ sensor.K = sensor.M * (2*pi*args.freq)^2;
+ sensor.C = 2*sqrt(sensor.M * sensor.K);
+ case 'accelerometer'
+ sensor.type = 2;
+
+ sensor.M = args.mass;
+ sensor.K = sensor.M * (2*pi*args.freq)^2;
+ sensor.C = 2*sqrt(sensor.M * sensor.K);
+ sensor.G = -sensor.K/sensor.M;
+ case 'none'
+ sensor.type = 3;
+ end
+#+end_src
+
+*** Populate the =stewart= structure
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ stewart.sensors.inertial = sensor;
+#+end_src
+
+
+
+** =inverseKinematics=: Compute Inverse Kinematics
+:PROPERTIES:
+:header-args:matlab+: :tangle matlab/src/inverseKinematics.m
+:header-args:matlab+: :comments none :mkdirp yes :eval no
+:END:
+
+*** Theory
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+For inverse kinematic analysis, it is assumed that the position ${}^A\bm{P}$ and orientation of the moving platform ${}^A\bm{R}_B$ are given and the problem is to obtain the joint variables, namely, $\bm{L} = [l_1, l_2, \dots, l_6]^T$.
+
+From the geometry of the manipulator, the loop closure for each limb, $i = 1, 2, \dots, 6$ can be written as
+\begin{align*}
+ l_i {}^A\hat{\bm{s}}_i &= {}^A\bm{A} + {}^A\bm{b}_i - {}^A\bm{a}_i \\
+ &= {}^A\bm{A} + {}^A\bm{R}_b {}^B\bm{b}_i - {}^A\bm{a}_i
+\end{align*}
+
+To obtain the length of each actuator and eliminate $\hat{\bm{s}}_i$, it is sufficient to dot multiply each side by itself:
+\begin{equation}
+ l_i^2 \left[ {}^A\hat{\bm{s}}_i^T {}^A\hat{\bm{s}}_i \right] = \left[ {}^A\bm{P} + {}^A\bm{R}_B {}^B\bm{b}_i - {}^A\bm{a}_i \right]^T \left[ {}^A\bm{P} + {}^A\bm{R}_B {}^B\bm{b}_i - {}^A\bm{a}_i \right]
+\end{equation}
+
+Hence, for $i = 1, 2, \dots, 6$, each limb length can be uniquely determined by:
+\begin{equation}
+ l_i = \sqrt{{}^A\bm{P}^T {}^A\bm{P} + {}^B\bm{b}_i^T {}^B\bm{b}_i + {}^A\bm{a}_i^T {}^A\bm{a}_i - 2 {}^A\bm{P}^T {}^A\bm{a}_i + 2 {}^A\bm{P}^T \left[{}^A\bm{R}_B {}^B\bm{b}_i\right] - 2 \left[{}^A\bm{R}_B {}^B\bm{b}_i\right]^T {}^A\bm{a}_i}
+\end{equation}
+
+If the position and orientation of the moving platform lie in the feasible workspace of the manipulator, one unique solution to the limb length is determined by the above equation.
+Otherwise, when the limbs' lengths derived yield complex numbers, then the position or orientation of the moving platform is not reachable.
+
+*** Function description
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ function [Li, dLi] = inverseKinematics(stewart, args)
+ % inverseKinematics - Compute the needed length of each strut to have the wanted position and orientation of {B} with respect to {A}
+ %
+ % Syntax: [stewart] = inverseKinematics(stewart)
+ %
+ % Inputs:
+ % - stewart - A structure with the following fields
+ % - geometry.Aa [3x6] - The positions ai expressed in {A}
+ % - geometry.Bb [3x6] - The positions bi expressed in {B}
+ % - geometry.l [6x1] - Length of each strut
+ % - args - Can have the following fields:
+ % - AP [3x1] - The wanted position of {B} with respect to {A}
+ % - ARB [3x3] - The rotation matrix that gives the wanted orientation of {B} with respect to {A}
+ %
+ % Outputs:
+ % - Li [6x1] - The 6 needed length of the struts in [m] to have the wanted pose of {B} w.r.t. {A}
+ % - dLi [6x1] - The 6 needed displacement of the struts from the initial position in [m] to have the wanted pose of {B} w.r.t. {A}
+#+end_src
+
+*** Optional Parameters
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ arguments
+ stewart
+ args.AP (3,1) double {mustBeNumeric} = zeros(3,1)
+ args.ARB (3,3) double {mustBeNumeric} = eye(3)
+ end
+#+end_src
+
+*** Check the =stewart= structure elements
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ assert(isfield(stewart.geometry, 'Aa'), 'stewart.geometry should have attribute Aa')
+ Aa = stewart.geometry.Aa;
+
+ assert(isfield(stewart.geometry, 'Bb'), 'stewart.geometry should have attribute Bb')
+ Bb = stewart.geometry.Bb;
+
+ assert(isfield(stewart.geometry, 'l'), 'stewart.geometry should have attribute l')
+ l = stewart.geometry.l;
+#+end_src
+
+
+*** Compute
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ Li = sqrt(args.AP'*args.AP + diag(Bb'*Bb) + diag(Aa'*Aa) - (2*args.AP'*Aa)' + (2*args.AP'*(args.ARB*Bb))' - diag(2*(args.ARB*Bb)'*Aa));
+#+end_src
+
+#+begin_src matlab
+ dLi = Li-l;
+#+end_src
+
+** =describeMicroStationSetup=
+:PROPERTIES:
+:header-args:matlab+: :tangle matlab/src/describeMicroStationSetup.m
+:header-args:matlab+: :comments none :mkdirp yes :eval no
+:END:
+
+*** Function description
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ function [] = describeMicroStationSetup()
+ % describeMicroStationSetup -
+ %
+ % Syntax: [] = describeMicroStationSetup()
+ %
+ % Inputs:
+ % - -
+ %
+ % Outputs:
+ % - -
+#+end_src
+
+*** Simscape Configuration
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ load('./mat/conf_simscape.mat', 'conf_simscape');
+#+end_src
+
+#+begin_src matlab
+ fprintf('Simscape Configuration:\n');
+
+ if conf_simscape.type == 1
+ fprintf('- Gravity is included\n');
+ else
+ fprintf('- Gravity is not included\n');
+ end
+
+ fprintf('\n');
+#+end_src
+
+*** Disturbances
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ load('./mat/nass_disturbances.mat', 'args');
+#+end_src
+
+#+begin_src matlab
+ fprintf('Disturbances:\n');
+ if ~args.enable
+ fprintf('- No disturbance is included\n');
+ else
+ if args.Dwx && args.Dwy && args.Dwz
+ fprintf('- Ground motion\n');
+ end
+ if args.Fty_x && args.Fty_z
+ fprintf('- Vibrations of the Translation Stage\n');
+ end
+ if args.Frz_z
+ fprintf('- Vibrations of the Spindle\n');
+ end
+ end
+ fprintf('\n');
+#+end_src
+
+*** References
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ load('./mat/nass_references.mat', 'args');
+#+end_src
+
+#+begin_src matlab
+ fprintf('Reference Tracking:\n');
+ fprintf('- Translation Stage:\n');
+ switch args.Dy_type
+ case 'constant'
+ fprintf(' - Constant Position\n');
+ fprintf(' - Dy = %.0f [mm]\n', args.Dy_amplitude*1e3);
+ case 'triangular'
+ fprintf(' - Triangular Path\n');
+ fprintf(' - Amplitude = %.0f [mm]\n', args.Dy_amplitude*1e3);
+ fprintf(' - Period = %.0f [s]\n', args.Dy_period);
+ case 'sinusoidal'
+ fprintf(' - Sinusoidal Path\n');
+ fprintf(' - Amplitude = %.0f [mm]\n', args.Dy_amplitude*1e3);
+ fprintf(' - Period = %.0f [s]\n', args.Dy_period);
+ end
+
+ fprintf('- Tilt Stage:\n');
+ switch args.Ry_type
+ case 'constant'
+ fprintf(' - Constant Position\n');
+ fprintf(' - Ry = %.0f [mm]\n', args.Ry_amplitude*1e3);
+ case 'triangular'
+ fprintf(' - Triangular Path\n');
+ fprintf(' - Amplitude = %.0f [mm]\n', args.Ry_amplitude*1e3);
+ fprintf(' - Period = %.0f [s]\n', args.Ry_period);
+ case 'sinusoidal'
+ fprintf(' - Sinusoidal Path\n');
+ fprintf(' - Amplitude = %.0f [mm]\n', args.Ry_amplitude*1e3);
+ fprintf(' - Period = %.0f [s]\n', args.Ry_period);
+ end
+
+ fprintf('- Spindle:\n');
+ switch args.Rz_type
+ case 'constant'
+ fprintf(' - Constant Position\n');
+ fprintf(' - Rz = %.0f [deg]\n', 180/pi*args.Rz_amplitude);
+ case { 'rotating', 'rotating-not-filtered' }
+ fprintf(' - Rotating\n');
+ fprintf(' - Speed = %.0f [rpm]\n', 60/args.Rz_period);
+ end
+
+
+ fprintf('- Micro Hexapod:\n');
+ switch args.Dh_type
+ case 'constant'
+ fprintf(' - Constant Position\n');
+ fprintf(' - Dh = %.0f, %.0f, %.0f [mm]\n', args.Dh_pos(1), args.Dh_pos(2), args.Dh_pos(3));
+ fprintf(' - Rh = %.0f, %.0f, %.0f [deg]\n', args.Dh_pos(4), args.Dh_pos(5), args.Dh_pos(6));
+ end
+
+ fprintf('\n');
+#+end_src
+
+*** Controller
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ load('./mat/controller.mat', 'controller');
+#+end_src
+
+#+begin_src matlab
+ fprintf('Controller:\n');
+ fprintf('- %s\n', controller.name);
+ fprintf('\n');
+#+end_src
+
+*** Micro-Station
+:PROPERTIES:
+:UNNUMBERED: t
+:END:
+#+begin_src matlab
+ load('./mat/stages.mat', 'ground', 'granite', 'ty', 'ry', 'rz', 'micro_hexapod', 'axisc');
+#+end_src
+
+#+begin_src matlab
+ fprintf('Micro Station:\n');
+
+ if granite.type == 1 && ...
+ ty.type == 1 && ...
+ ry.type == 1 && ...
+ rz.type == 1 && ...
+ micro_hexapod.type == 1;
+ fprintf('- All stages are rigid\n');
+ elseif granite.type == 2 && ...
+ ty.type == 2 && ...
+ ry.type == 2 && ...
+ rz.type == 2 && ...
+ micro_hexapod.type == 2;
+ fprintf('- All stages are flexible\n');
+ else
+ if granite.type == 1 || granite.type == 4
+ fprintf('- Granite is rigid\n');
+ else
+ fprintf('- Granite is flexible\n');
+ end
+ if ty.type == 1 || ty.type == 4
+ fprintf('- Translation Stage is rigid\n');
+ else
+ fprintf('- Translation Stage is flexible\n');
+ end
+ if ry.type == 1 || ry.type == 4
+ fprintf('- Tilt Stage is rigid\n');
+ else
+ fprintf('- Tilt Stage is flexible\n');
+ end
+ if rz.type == 1 || rz.type == 4
+ fprintf('- Spindle is rigid\n');
+ else
+ fprintf('- Spindle is flexible\n');
+ end
+ if micro_hexapod.type == 1 || micro_hexapod.type == 4
+ fprintf('- Micro Hexapod is rigid\n');
+ else
+ fprintf('- Micro Hexapod is flexible\n');
+ end
+
+ end
+
+ fprintf('\n');
+#+end_src
+
+** =computeReferencePose=
+:PROPERTIES:
+:header-args:matlab+: :tangle matlab/src/computeReferencePose.m
:header-args:matlab+: :comments none :mkdirp yes :eval no
:END:
#+begin_src matlab
- function [geophone] = initializeZAxisGeophone(args)
- arguments
- args.mass (1,1) double {mustBeNumeric, mustBePositive} = 1e-3 % [kg]
- args.freq (1,1) double {mustBeNumeric, mustBePositive} = 1 % [Hz]
- end
+ function [WTr] = computeReferencePose(Dy, Ry, Rz, Dh, Dn)
+ % computeReferencePose - Compute the homogeneous transformation matrix corresponding to the wanted pose of the sample
+ %
+ % Syntax: [WTr] = computeReferencePose(Dy, Ry, Rz, Dh, Dn)
+ %
+ % Inputs:
+ % - Dy - Reference of the Translation Stage [m]
+ % - Ry - Reference of the Tilt Stage [rad]
+ % - Rz - Reference of the Spindle [rad]
+ % - Dh - Reference of the Micro Hexapod (Pitch, Roll, Yaw angles) [m, m, m, rad, rad, rad]
+ % - Dn - Reference of the Nano Hexapod [m, m, m, rad, rad, rad]
+ %
+ % Outputs:
+ % - WTr -
- %%
- geophone.m = args.mass;
+ %% Translation Stage
+ Rty = [1 0 0 0;
+ 0 1 0 Dy;
+ 0 0 1 0;
+ 0 0 0 1];
- %% The Stiffness is set to have the damping resonance frequency
- geophone.k = geophone.m * (2*pi*args.freq)^2;
+ %% Tilt Stage - Pure rotating aligned with Ob
+ Rry = [ cos(Ry) 0 sin(Ry) 0;
+ 0 1 0 0;
+ -sin(Ry) 0 cos(Ry) 0;
+ 0 0 0 1];
- %% We set the damping value to have critical damping
- geophone.c = 2*sqrt(geophone.m * geophone.k);
-#+end_src
-
-#+begin_src matlab
-if exist('./mat', 'dir')
- if exist('./mat/geophone_z_axis.mat', 'file')
- save('mat/geophone_z_axis.mat', 'geophone', '-append');
- else
- save('mat/geophone_z_axis.mat', 'geophone');
- end
-elseif exist('./matlab', 'dir')
- if exist('./matlab/mat/geophone_z_axis.mat', 'file')
- save('matlab/mat/geophone_z_axis.mat', 'geophone', '-append');
- else
- save('matlab/mat/geophone_z_axis.mat', 'geophone');
- end
-end
-#+end_src
+ %% Spindle - Rotation along the Z axis
+ Rrz = [cos(Rz) -sin(Rz) 0 0 ;
+ sin(Rz) cos(Rz) 0 0 ;
+ 0 0 1 0 ;
+ 0 0 0 1 ];
-** Z-Axis Accelerometer
-:PROPERTIES:
-:header-args:matlab+: :tangle matlab/src/initializeZAxisAccelerometer.m
-:header-args:matlab+: :comments none :mkdirp yes :eval no
-:END:
+ %% Micro-Hexapod
+ Rhx = [1 0 0;
+ 0 cos(Dh(4)) -sin(Dh(4));
+ 0 sin(Dh(4)) cos(Dh(4))];
-#+begin_src matlab
- function [accelerometer] = initializeZAxisAccelerometer(args)
- arguments
- args.mass (1,1) double {mustBeNumeric, mustBePositive} = 1e-3 % [kg]
- args.freq (1,1) double {mustBeNumeric, mustBePositive} = 5e3 % [Hz]
- end
+ Rhy = [ cos(Dh(5)) 0 sin(Dh(5));
+ 0 1 0;
+ -sin(Dh(5)) 0 cos(Dh(5))];
- %%
- accelerometer.m = args.mass;
+ Rhz = [cos(Dh(6)) -sin(Dh(6)) 0;
+ sin(Dh(6)) cos(Dh(6)) 0;
+ 0 0 1];
- %% The Stiffness is set to have the damping resonance frequency
- accelerometer.k = accelerometer.m * (2*pi*args.freq)^2;
+ Rh = [1 0 0 Dh(1) ;
+ 0 1 0 Dh(2) ;
+ 0 0 1 Dh(3) ;
+ 0 0 0 1 ];
- %% We set the damping value to have critical damping
- accelerometer.c = 2*sqrt(accelerometer.m * accelerometer.k);
+ Rh(1:3, 1:3) = Rhz*Rhy*Rhx;
- %% Gain correction of the accelerometer to have a unity gain until the resonance
- accelerometer.gain = -accelerometer.k/accelerometer.m;
+ %% Nano-Hexapod
+ Rnx = [1 0 0;
+ 0 cos(Dn(4)) -sin(Dn(4));
+ 0 sin(Dn(4)) cos(Dn(4))];
-#+end_src
+ Rny = [ cos(Dn(5)) 0 sin(Dn(5));
+ 0 1 0;
+ -sin(Dn(5)) 0 cos(Dn(5))];
-#+begin_src matlab
-if exist('./mat', 'dir')
- if exist('./mat/accelerometer_z_axis.mat', 'file')
- save('mat/accelerometer_z_axis.mat', 'accelerometer', '-append');
- else
- save('mat/accelerometer_z_axis.mat', 'accelerometer');
- end
-elseif exist('./matlab', 'dir')
- if exist('./matlab/mat/accelerometer_z_axis.mat', 'file')
- save('matlab/mat/accelerometer_z_axis.mat', 'accelerometer', '-append');
- else
- save('matlab/mat/accelerometer_z_axis.mat', 'accelerometer');
- end
-end
+ Rnz = [cos(Dn(6)) -sin(Dn(6)) 0;
+ sin(Dn(6)) cos(Dn(6)) 0;
+ 0 0 1];
+
+ Rn = [1 0 0 Dn(1) ;
+ 0 1 0 Dn(2) ;
+ 0 0 1 Dn(3) ;
+ 0 0 0 1 ];
+
+ Rn(1:3, 1:3) = Rnz*Rny*Rnx;
+
+ %% Total Homogeneous transformation
+ WTr = Rty*Rry*Rrz*Rh*Rn;
+ end
#+end_src
* Helping Functions :noexport: