diff --git a/mat/conf_log.mat b/mat/conf_log.mat index ec0c7b7..8fb5793 100644 Binary files a/mat/conf_log.mat and b/mat/conf_log.mat differ diff --git a/mat/conf_simscape.mat b/mat/conf_simscape.mat index 825cf1c..ab81889 100644 Binary files a/mat/conf_simscape.mat and b/mat/conf_simscape.mat differ diff --git a/mat/controller.mat b/mat/controller.mat index 1f85ef8..cc7c17e 100644 Binary files a/mat/controller.mat and b/mat/controller.mat differ diff --git a/mat/nass_disturbances.mat b/mat/nass_disturbances.mat index 354d356..8845b07 100644 Binary files a/mat/nass_disturbances.mat and b/mat/nass_disturbances.mat differ diff --git a/mat/nass_references.mat b/mat/nass_references.mat index e9904de..8c9d204 100644 Binary files a/mat/nass_references.mat and b/mat/nass_references.mat differ diff --git a/mat/stages.mat b/mat/stages.mat index c4221a6..8bb6055 100644 Binary files a/mat/stages.mat and b/mat/stages.mat differ diff --git a/matlab/Fixed_Based.slx b/matlab/Fixed_Based.slx new file mode 100644 index 0000000..d1bf72d Binary files /dev/null and b/matlab/Fixed_Based.slx differ diff --git a/matlab/Mobile_Platform.slx b/matlab/Mobile_Platform.slx new file mode 100644 index 0000000..54e2092 Binary files /dev/null and b/matlab/Mobile_Platform.slx differ diff --git a/matlab/micro_hexapod_strut.slx b/matlab/micro_hexapod_strut.slx new file mode 100644 index 0000000..a81cd16 Binary files /dev/null and b/matlab/micro_hexapod_strut.slx differ diff --git a/matlab/nano_hexapod_leg_rigid.slx b/matlab/nano_hexapod_leg_rigid.slx index 366b2d8..37ee93f 100644 Binary files a/matlab/nano_hexapod_leg_rigid.slx and b/matlab/nano_hexapod_leg_rigid.slx differ diff --git a/matlab/nano_hexapod_strut.slx b/matlab/nano_hexapod_strut.slx new file mode 100644 index 0000000..99e1112 Binary files /dev/null and b/matlab/nano_hexapod_strut.slx differ diff --git a/matlab/nass_model.slx b/matlab/nass_model.slx index 72e6102..0c7fd6d 100644 Binary files a/matlab/nass_model.slx and b/matlab/nass_model.slx differ diff --git a/matlab/stewart_strut.slx.r2019b b/matlab/stewart_strut.slx.r2019b new file mode 100644 index 0000000..ffe49ee Binary files /dev/null and b/matlab/stewart_strut.slx.r2019b differ diff --git a/matlab/z_axis_accelerometer.slx b/matlab/z_axis_accelerometer.slx new file mode 100644 index 0000000..df6785d Binary files /dev/null and b/matlab/z_axis_accelerometer.slx differ diff --git a/matlab/z_axis_geophone.slx b/matlab/z_axis_geophone.slx new file mode 100644 index 0000000..35ed473 Binary files /dev/null and b/matlab/z_axis_geophone.slx differ diff --git a/org/simscape_subsystems.org b/org/simscape_subsystems.org index dce5b01..7e39de6 100644 --- a/org/simscape_subsystems.org +++ b/org/simscape_subsystems.org @@ -861,25 +861,68 @@ The =rz= structure is saved. :UNNUMBERED: t :END: #+begin_src matlab - micro_hexapod = initializeFramesPositions('H', args.H, 'MO_B', args.MO_B); - micro_hexapod = generateGeneralConfiguration(micro_hexapod, 'FH', args.FH, 'FR', args.FR, 'FTh', args.FTh, 'MH', args.MH, 'MR', args.MR, 'MTh', args.MTh); - micro_hexapod = computeJointsPose(micro_hexapod); - micro_hexapod = initializeStrutDynamics(micro_hexapod, 'Ki', args.Ki, 'Ci', args.Ci); - micro_hexapod = initializeCylindricalPlatforms(micro_hexapod, 'Fpm', args.Fpm, 'Fph', args.Fph, 'Fpr', args.Fpr, 'Mpm', args.Mpm, 'Mph', args.Mph, 'Mpr', args.Mpr); - micro_hexapod = initializeCylindricalStruts(micro_hexapod, 'Fsm', args.Fsm, 'Fsh', args.Fsh, 'Fsr', args.Fsr, 'Msm', args.Msm, 'Msh', args.Msh, 'Msr', args.Msr); - micro_hexapod = computeJacobian(micro_hexapod); - [Li, dLi] = inverseKinematics(micro_hexapod, 'AP', args.AP, 'ARB', args.ARB); - micro_hexapod.Li = Li; - micro_hexapod.dLi = dLi; + stewart = initializeStewartPlatform(); + + stewart = initializeFramesPositions(stewart, ... + 'H', args.H, ... + 'MO_B', args.MO_B); + + stewart = generateGeneralConfiguration(stewart, ... + 'FH', args.FH, ... + 'FR', args.FR, ... + 'FTh', args.FTh, ... + 'MH', args.MH, ... + 'MR', args.MR, ... + 'MTh', args.MTh); + + stewart = computeJointsPose(stewart); +#+end_src + +#+begin_src matlab + stewart = initializeStrutDynamics(stewart, ... + 'K', args.Ki, ... + 'C', args.Ci); + + stewart = initializeJointDynamics(stewart, ... + 'type_F', 'universal_p', ... + 'type_M', 'spherical_p'); +#+end_src + +#+begin_src matlab + stewart = initializeCylindricalPlatforms(stewart, ... + 'Fpm', args.Fpm, ... + 'Fph', args.Fph, ... + 'Fpr', args.Fpr, ... + 'Mpm', args.Mpm, ... + 'Mph', args.Mph, ... + 'Mpr', args.Mpr); + + stewart = initializeCylindricalStruts(stewart, ... + 'Fsm', args.Fsm, ... + 'Fsh', args.Fsh, ... + 'Fsr', args.Fsr, ... + 'Msm', args.Msm, ... + 'Msh', args.Msh, ... + 'Msr', args.Msr); + + stewart = computeJacobian(stewart); + + stewart = initializeStewartPose(stewart, ... + 'AP', args.AP, ... + 'ARB', args.ARB); +#+end_src + +#+begin_src matlab + 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('mat/Foffset.mat', 'Fhm'); - micro_hexapod.dLeq = -Fhm'./args.Ki; + stewart.actuators.dLeq = -Fhm'./args.Ki; else - micro_hexapod.dLeq = zeros(6,1); + stewart.actuators.dLeq = zeros(6,1); end #+end_src @@ -890,17 +933,17 @@ Equilibrium position of the each joint. #+begin_src matlab switch args.type case 'none' - micro_hexapod.type = 0; + stewart.type = 0; case 'rigid' - micro_hexapod.type = 1; + stewart.type = 1; case 'flexible' - micro_hexapod.type = 2; + stewart.type = 2; case 'modal-analysis' - micro_hexapod.type = 3; + stewart.type = 3; case 'init' - micro_hexapod.type = 4; + stewart.type = 4; case 'compliance' - micro_hexapod.type = 5; + stewart.type = 5; end #+end_src @@ -910,6 +953,7 @@ Equilibrium position of the each joint. :END: The =micro_hexapod= structure is saved. #+begin_src matlab + micro_hexapod = stewart; save('./mat/stages.mat', 'micro_hexapod', '-append'); #+end_src @@ -1238,6 +1282,17 @@ The =mirror= structure is saved. args.actuator char {mustBeMember(args.actuator,{'piezo', 'lorentz'})} = 'piezo' args.k (1,1) double {mustBeNumeric} = -1 args.c (1,1) double {mustBeNumeric} = -1 + % initializeJointDynamics + args.type_F char {mustBeMember(args.type_F,{'universal', 'spherical', 'universal_p', 'spherical_p'})} = 'universal' + args.type_M char {mustBeMember(args.type_M,{'universal', 'spherical', 'universal_p', 'spherical_p'})} = 'spherical' + args.Kf_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 15*ones(6,1) + args.Cf_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-4*ones(6,1) + args.Kt_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 20*ones(6,1) + args.Ct_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-3*ones(6,1) + args.Kf_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 15*ones(6,1) + args.Cf_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-4*ones(6,1) + args.Kt_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 20*ones(6,1) + args.Ct_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-3*ones(6,1) % initializeCylindricalPlatforms args.Fpm (1,1) double {mustBeNumeric, mustBePositive} = 1 args.Fph (1,1) double {mustBeNumeric, mustBePositive} = 10e-3 @@ -1267,32 +1322,55 @@ The =mirror= structure is saved. :UNNUMBERED: t :END: #+begin_src matlab - nano_hexapod = initializeFramesPositions('H', args.H, 'MO_B', args.MO_B); - nano_hexapod = generateGeneralConfiguration(nano_hexapod, 'FH', args.FH, 'FR', args.FR, 'FTh', args.FTh, 'MH', args.MH, 'MR', args.MR, 'MTh', args.MTh); - nano_hexapod = computeJointsPose(nano_hexapod); + stewart = initializeStewartPlatform(); + + stewart = initializeFramesPositions(stewart, 'H', args.H, 'MO_B', args.MO_B); + + stewart = generateGeneralConfiguration(stewart, 'FH', args.FH, 'FR', args.FR, 'FTh', args.FTh, 'MH', args.MH, 'MR', args.MR, 'MTh', args.MTh); + + stewart = computeJointsPose(stewart); #+end_src #+begin_src matlab if args.k > 0 && args.c > 0 - nano_hexapod = initializeStrutDynamics(nano_hexapod, 'Ki', args.k*ones(6,1), 'Ci', args.c*ones(6,1)); + stewart = initializeStrutDynamics(stewart, 'K', args.k*ones(6,1), 'C', args.c*ones(6,1)); elseif args.k > 0 - nano_hexapod = initializeStrutDynamics(nano_hexapod, 'Ki', args.k*ones(6,1), 'Ci', 1.5*sqrt(args.k)*ones(6,1)); + stewart = initializeStrutDynamics(stewart, 'K', args.k*ones(6,1), 'C', 1.5*sqrt(args.k)*ones(6,1)); elseif strcmp(args.actuator, 'piezo') - nano_hexapod = initializeStrutDynamics(nano_hexapod, 'Ki', 1e7*ones(6,1), 'Ci', 1e2*ones(6,1)); + stewart = initializeStrutDynamics(stewart, 'K', 1e7*ones(6,1), 'C', 1e2*ones(6,1)); elseif strcmp(args.actuator, 'lorentz') - nano_hexapod = initializeStrutDynamics(nano_hexapod, 'Ki', 1e4*ones(6,1), 'Ci', 1e2*ones(6,1)); + stewart = initializeStrutDynamics(stewart, 'K', 1e4*ones(6,1), 'C', 1e2*ones(6,1)); else error('args.actuator should be piezo or lorentz'); end #+end_src #+begin_src matlab - nano_hexapod = initializeCylindricalPlatforms(nano_hexapod, 'Fpm', args.Fpm, 'Fph', args.Fph, 'Fpr', args.Fpr, 'Mpm', args.Mpm, 'Mph', args.Mph, 'Mpr', args.Mpr); - nano_hexapod = initializeCylindricalStruts(nano_hexapod, 'Fsm', args.Fsm, 'Fsh', args.Fsh, 'Fsr', args.Fsr, 'Msm', args.Msm, 'Msh', args.Msh, 'Msr', args.Msr); - nano_hexapod = computeJacobian(nano_hexapod); - [Li, dLi] = inverseKinematics(nano_hexapod, 'AP', args.AP, 'ARB', args.ARB); - nano_hexapod.Li = Li; - nano_hexapod.dLi = dLi; + stewart = initializeJointDynamics(stewart, ... + 'type_F', args.type_F, ... + 'type_M', args.type_M, ... + 'Kf_M' , args.Kf_M, ... + 'Cf_M' , args.Cf_M, ... + 'Kt_M' , args.Kt_M, ... + 'Ct_M' , args.Ct_M, ... + 'Kf_F' , args.Kf_F, ... + 'Cf_F' , args.Cf_F, ... + 'Kt_F' , args.Kt_F, ... + 'Ct_F' , args.Ct_F); +#+end_src + +#+begin_src matlab + stewart = initializeCylindricalPlatforms(stewart, 'Fpm', args.Fpm, 'Fph', args.Fph, 'Fpr', args.Fpr, 'Mpm', args.Mpm, 'Mph', args.Mph, 'Mpr', args.Mpr); + + stewart = initializeCylindricalStruts(stewart, 'Fsm', args.Fsm, 'Fsh', args.Fsh, 'Fsr', args.Fsr, 'Msm', args.Msm, 'Msh', args.Msh, 'Msr', args.Msr); + + stewart = computeJacobian(stewart); + + stewart = initializeStewartPose(stewart, 'AP', args.AP, 'ARB', args.ARB); +#+end_src + +#+begin_src matlab + stewart = initializeInertialSensor(stewart, 'type', 'accelerometer'); #+end_src Equilibrium position of the each joint. @@ -1300,9 +1378,9 @@ Equilibrium position of the each joint. if args.Foffset && ~strcmp(args.type, 'none') && ~strcmp(args.type, 'rigid') && ~strcmp(args.type, 'init') load('mat/Foffset.mat', 'Fnm'); - nano_hexapod.dLeq = -Fnm'./nano_hexapod.Ki; + stewart.actuators.dLeq = -Fnm'./stewart.Ki; else - nano_hexapod.dLeq = args.dLeq; + stewart.actuators.dLeq = args.dLeq; end #+end_src @@ -1313,13 +1391,13 @@ Equilibrium position of the each joint. #+begin_src matlab switch args.type case 'none' - nano_hexapod.type = 0; + stewart.type = 0; case 'rigid' - nano_hexapod.type = 1; + stewart.type = 1; case 'flexible' - nano_hexapod.type = 2; + stewart.type = 2; case 'init' - nano_hexapod.type = 4; + stewart.type = 4; end #+end_src @@ -1328,6 +1406,7 @@ Equilibrium position of the each joint. :UNNUMBERED: t :END: #+begin_src matlab + nano_hexapod = stewart; save('./mat/stages.mat', 'nano_hexapod', '-append'); #+end_src diff --git a/org/stewart_platform.org b/org/stewart_platform.org index cf29ecd..0f55f06 100644 --- a/org/stewart_platform.org +++ b/org/stewart_platform.org @@ -42,6 +42,68 @@ For Simscape, we need: - The position of the frame $\{A\}$ with respect to the frame $\{F\}$: ${}^{F}\bm{O}_{A}$ - The position of the frame $\{B\}$ with respect to the frame $\{M\}$: ${}^{M}\bm{O}_{B}$ +* =initializeStewartPlatform=: Initialize the Stewart Platform structure +:PROPERTIES: +:header-args:matlab+: :tangle ../src/initializeStewartPlatform.m +:header-args:matlab+: :comments none :mkdirp yes :eval no +:END: +<> + +This Matlab function is accessible [[file:../src/initializeStewartPlatform.m][here]]. + +** 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 ../src/initializeFramesPositions.m @@ -49,14 +111,26 @@ For Simscape, we need: :END: <> -This Matlab function is accessible [[file:src/initializeFramesPositions.m][here]]. +This Matlab function is accessible [[file:../src/initializeFramesPositions.m][here]]. + +** 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(args) + function [stewart] = initializeFramesPositions(stewart, args) % initializeFramesPositions - Initialize the positions of frames {A}, {B}, {F} and {M} % - % Syntax: [stewart] = initializeFramesPositions(args) + % Syntax: [stewart] = initializeFramesPositions(stewart, args) % % Inputs: % - args - Can have the following fields: @@ -65,132 +139,117 @@ This Matlab function is accessible [[file:src/initializeFramesPositions.m][here] % % Outputs: % - stewart - A structure with the following fields: - % - H [1x1] - Total Height of the Stewart Platform [m] - % - FO_M [3x1] - Position of {M} with respect to {F} [m] - % - MO_B [3x1] - Position of {B} with respect to {M} [m] - % - FO_A [3x1] - Position of {A} with respect to {F} [m] + % - 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 -** Documentation - -#+name: fig:stewart-frames-position -#+caption: Definition of the position of the frames -[[file:figs/stewart-frames-position.png]] - ** 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 -** Initialize the Stewart structure -#+begin_src matlab - stewart = struct(); -#+end_src - ** Compute the position of each frame -#+begin_src matlab - stewart.H = args.H; % Total Height of the Stewart Platform [m] - - stewart.FO_M = [0; 0; stewart.H]; % Position of {M} with respect to {F} [m] - - stewart.MO_B = [0; 0; args.MO_B]; % Position of {B} with respect to {M} [m] - - stewart.FO_A = stewart.MO_B + stewart.FO_M; % Position of {A} with respect to {F} [m] -#+end_src - -* Initialize the position of the Joints -** =generateCubicConfiguration=: Generate a Cubic Configuration :PROPERTIES: -:header-args:matlab+: :tangle ../src/generateCubicConfiguration.m -:header-args:matlab+: :comments none :mkdirp yes :eval no +:UNNUMBERED: t :END: -<> - -This Matlab function is accessible [[file:src/generateCubicConfiguration.m][here]]. - -*** Function description #+begin_src matlab - function [stewart] = generateCubicConfiguration(stewart, args) - % generateCubicConfiguration - Generate a Cubic Configuration - % - % Syntax: [stewart] = generateCubicConfiguration(stewart, args) - % - % Inputs: - % - stewart - A structure with the following fields - % - H [1x1] - Total height of the platform [m] - % - args - Can have the following fields: - % - Hc [1x1] - Height of the "useful" part of the cube [m] - % - FOc [1x1] - Height of the center of the cube with respect to {F} [m] - % - FHa [1x1] - Height of the plane joining the points ai with respect to the frame {F} [m] - % - MHb [1x1] - Height of the plane joining the points bi with respect to the frame {M} [m] - % - % Outputs: - % - stewart - updated Stewart structure with the added fields: - % - Fa [3x6] - Its i'th column is the position vector of joint ai with respect to {F} - % - Mb [3x6] - Its i'th column is the position vector of joint bi with respect to {M} + 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 -*** Documentation -#+name: fig:cubic-configuration-definition -#+caption: Cubic Configuration -[[file:figs/cubic-configuration-definition.png]] - -*** Optional Parameters +** Populate the =stewart= structure +:PROPERTIES: +:UNNUMBERED: t +:END: #+begin_src matlab - arguments - stewart - args.Hc (1,1) double {mustBeNumeric, mustBePositive} = 60e-3 - args.FOc (1,1) double {mustBeNumeric} = 50e-3 - args.FHa (1,1) double {mustBeNumeric, mustBePositive} = 15e-3 - args.MHb (1,1) double {mustBeNumeric, mustBePositive} = 15e-3 - end + 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 -*** Position of the Cube -We define the useful points of the cube with respect to the Cube's center. -${}^{C}C$ are the 6 vertices of the cubes expressed in a frame {C} which is -located at the center of the cube and aligned with {F} and {M}. - -#+begin_src matlab - sx = [ 2; -1; -1]; - sy = [ 0; 1; -1]; - sz = [ 1; 1; 1]; - - R = [sx, sy, sz]./vecnorm([sx, sy, sz]); - - L = args.Hc*sqrt(3); - - Cc = R'*[[0;0;L],[L;0;L],[L;0;0],[L;L;0],[0;L;0],[0;L;L]] - [0;0;1.5*args.Hc]; - - CCf = [Cc(:,1), Cc(:,3), Cc(:,3), Cc(:,5), Cc(:,5), Cc(:,1)]; % CCf(:,i) corresponds to the bottom cube's vertice corresponding to the i'th leg - CCm = [Cc(:,2), Cc(:,2), Cc(:,4), Cc(:,4), Cc(:,6), Cc(:,6)]; % CCm(:,i) corresponds to the top cube's vertice corresponding to the i'th leg -#+end_src - -*** Compute the pose -We can compute the vector of each leg ${}^{C}\hat{\bm{s}}_{i}$ (unit vector from ${}^{C}C_{f}$ to ${}^{C}C_{m}$). -#+begin_src matlab - CSi = (CCm - CCf)./vecnorm(CCm - CCf); -#+end_src - -We now which to compute the position of the joints $a_{i}$ and $b_{i}$. -#+begin_src matlab - stewart.Fa = CCf + [0; 0; args.FOc] + ((args.FHa-(args.FOc-args.Hc/2))./CSi(3,:)).*CSi; - stewart.Mb = CCf + [0; 0; args.FOc-stewart.H] + ((stewart.H-args.MHb-(args.FOc-args.Hc/2))./CSi(3,:)).*CSi; -#+end_src - -** =generateGeneralConfiguration=: Generate a Very General Configuration +* =generateGeneralConfiguration=: Generate a Very General Configuration :PROPERTIES: :header-args:matlab+: :tangle ../src/generateGeneralConfiguration.m :header-args:matlab+: :comments none :mkdirp yes :eval no :END: <> -This Matlab function is accessible [[file:src/generateGeneralConfiguration.m][here]]. +This Matlab function is accessible [[file:../src/generateGeneralConfiguration.m][here]]. -*** Function description +** 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 + \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 @@ -208,40 +267,51 @@ This Matlab function is accessible [[file:src/generateGeneralConfiguration.m][he % % Outputs: % - stewart - updated Stewart structure with the added fields: - % - Fa [3x6] - Its i'th column is the position vector of joint ai with respect to {F} - % - Mb [3x6] - Its i'th column is the position vector of joint bi with respect to {M} + % - 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 -*** Documentation -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. - -*** Optional Parameters +** 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} = 90e-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} = 70e-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 +** Compute the pose +:PROPERTIES: +:UNNUMBERED: t +:END: #+begin_src matlab - stewart.Fa = zeros(3,6); - stewart.Mb = zeros(3,6); + Fa = zeros(3,6); + Mb = zeros(3,6); #+end_src #+begin_src matlab for i = 1:6 - stewart.Fa(:,i) = [args.FR*cos(args.FTh(i)); args.FR*sin(args.FTh(i)); args.FH]; - stewart.Mb(:,i) = [args.MR*cos(args.MTh(i)); args.MR*sin(args.MTh(i)); -args.MH]; + 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 ../src/computeJointsPose.m @@ -249,9 +319,21 @@ The radius of the circles can be chosen as well as the angles where the joints a :END: <> -This Matlab function is accessible [[file:src/computeJointsPose.m][here]]. +This Matlab function is accessible [[file:../src/computeJointsPose.m][here]]. + +** 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 - @@ -260,161 +342,185 @@ This Matlab function is accessible [[file:src/computeJointsPose.m][here]]. % % Inputs: % - stewart - A structure with the following fields - % - Fa [3x6] - Its i'th column is the position vector of joint ai with respect to {F} - % - Mb [3x6] - Its i'th column is the position vector of joint bi with respect to {M} - % - FO_A [3x1] - Position of {A} with respect to {F} - % - MO_B [3x1] - Position of {B} with respect to {M} - % - FO_M [3x1] - Position of {M} with respect to {F} + % - 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 - % - Aa [3x6] - The i'th column is the position of ai with respect to {A} - % - Ab [3x6] - The i'th column is the position of bi with respect to {A} - % - Ba [3x6] - The i'th column is the position of ai with respect to {B} - % - Bb [3x6] - The i'th column is the position of bi with respect to {B} - % - l [6x1] - The i'th element is the initial length of strut i - % - As [3x6] - The i'th column is the unit vector of strut i expressed in {A} - % - Bs [3x6] - The i'th column is the unit vector of strut i expressed in {B} - % - FRa [3x3x6] - The i'th 3x3 array is the rotation matrix to orientate the bottom of the i'th strut from {F} - % - MRb [3x3x6] - The i'th 3x3 array is the rotation matrix to orientate the top of the i'th strut from {M} + % - 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 -** Documentation +** 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; -#+name: fig:stewart-struts -#+caption: Position and orientation of the struts -[[file:figs/stewart-struts.png]] + 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 - stewart.Aa = stewart.Fa - repmat(stewart.FO_A, [1, 6]); - stewart.Bb = stewart.Mb - repmat(stewart.MO_B, [1, 6]); + Aa = Fa - repmat(FO_A, [1, 6]); + Bb = Mb - repmat(MO_B, [1, 6]); - stewart.Ab = stewart.Bb - repmat(-stewart.MO_B-stewart.FO_M+stewart.FO_A, [1, 6]); - stewart.Ba = stewart.Aa - repmat( stewart.MO_B+stewart.FO_M-stewart.FO_A, [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 - stewart.As = (stewart.Ab - stewart.Aa)./vecnorm(stewart.Ab - stewart.Aa); % As_i is the i'th vector of As + As = (Ab - Aa)./vecnorm(Ab - Aa); % As_i is the i'th vector of As - stewart.l = vecnorm(stewart.Ab - stewart.Aa)'; + l = vecnorm(Ab - Aa)'; #+end_src #+begin_src matlab - stewart.Bs = (stewart.Bb - stewart.Ba)./vecnorm(stewart.Bb - stewart.Ba); + Bs = (Bb - Ba)./vecnorm(Bb - Ba); #+end_src ** Compute the orientation of the Joints +:PROPERTIES: +:UNNUMBERED: t +:END: #+begin_src matlab - stewart.FRa = zeros(3,3,6); - stewart.MRb = zeros(3,3,6); + FRa = zeros(3,3,6); + MRb = zeros(3,3,6); for i = 1:6 - stewart.FRa(:,:,i) = [cross([0;1;0], stewart.As(:,i)) , cross(stewart.As(:,i), cross([0;1;0], stewart.As(:,i))) , stewart.As(:,i)]; - stewart.FRa(:,:,i) = stewart.FRa(:,:,i)./vecnorm(stewart.FRa(:,:,i)); + 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)); - stewart.MRb(:,:,i) = [cross([0;1;0], stewart.Bs(:,i)) , cross(stewart.Bs(:,i), cross([0;1;0], stewart.Bs(:,i))) , stewart.Bs(:,i)]; - stewart.MRb(:,:,i) = stewart.MRb(:,:,i)./vecnorm(stewart.MRb(:,:,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 -* =initializeStrutDynamics=: Add Stiffness and Damping properties of each strut +** Populate the =stewart= structure :PROPERTIES: -:header-args:matlab+: :tangle ../src/initializeStrutDynamics.m +: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 + +* =initializeStewartPose=: Determine the initial stroke in each leg to have the wanted pose +:PROPERTIES: +:header-args:matlab+: :tangle ../src/initializeStewartPose.m :header-args:matlab+: :comments none :mkdirp yes :eval no :END: -<> +<> -This Matlab function is accessible [[file:src/initializeStrutDynamics.m][here]]. +This Matlab function is accessible [[file:../src/initializeStewartPose.m][here]]. ** Function description +:PROPERTIES: +:UNNUMBERED: t +:END: #+begin_src matlab - function [stewart] = initializeStrutDynamics(stewart, args) - % initializeStrutDynamics - Add Stiffness and Damping properties of each strut + 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] = initializeStrutDynamics(args) + % Syntax: [stewart] = initializeStewartPose(stewart, args) % % Inputs: - % - args - Structure with the following fields: - % - Ki [6x1] - Stiffness of each strut [N/m] - % - Ci [6x1] - Damping of each strut [N/(m/s)] + % - 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: - % - Ki [6x1] - Stiffness of each strut [N/m] - % - Ci [6x1] - Damping of each strut [N/(m/s)] + % - 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.Ki (6,1) double {mustBeNumeric, mustBePositive} = 1e6*ones(6,1) - args.Ci (6,1) double {mustBeNumeric, mustBePositive} = 1e3*ones(6,1) + args.AP (3,1) double {mustBeNumeric} = zeros(3,1) + args.ARB (3,3) double {mustBeNumeric} = eye(3) end #+end_src -** Add Stiffness and Damping properties of each strut -#+begin_src matlab - stewart.Ki = args.Ki; - stewart.Ci = args.Ci; -#+end_src - -* =computeJacobian=: Compute the Jacobian Matrix +** Use the Inverse Kinematic function :PROPERTIES: -:header-args:matlab+: :tangle ../src/computeJacobian.m -:header-args:matlab+: :comments none :mkdirp yes :eval no +:UNNUMBERED: t :END: -<> - -This Matlab function is accessible [[file:src/computeJacobian.m][here]]. - -** Function description #+begin_src matlab - function [stewart] = computeJacobian(stewart) - % computeJacobian - - % - % Syntax: [stewart] = computeJacobian(stewart) - % - % Inputs: - % - stewart - With at least the following fields: - % - As [3x6] - The 6 unit vectors for each strut expressed in {A} - % - Ab [3x6] - The 6 position of the joints bi expressed in {A} - % - % Outputs: - % - stewart - With the 3 added field: - % - J [6x6] - The Jacobian Matrix - % - K [6x6] - The Stiffness Matrix - % - C [6x6] - The Compliance Matrix + [Li, dLi] = inverseKinematics(stewart, 'AP', args.AP, 'ARB', args.ARB); #+end_src -** Compute Jacobian Matrix +** Populate the =stewart= structure +:PROPERTIES: +:UNNUMBERED: t +:END: #+begin_src matlab - stewart.J = [stewart.As' , cross(stewart.Ab, stewart.As)']; + stewart.actuators.Leq = dLi; #+end_src -** Compute Stiffness Matrix -#+begin_src matlab - stewart.K = stewart.J'*diag(stewart.Ki)*stewart.J; -#+end_src - -** Compute Compliance Matrix -#+begin_src matlab - stewart.C = inv(stewart.K); -#+end_src - -* Initialize the Geometry of the Mechanical Elements -** =initializeCylindricalPlatforms=: Initialize the geometry of the Fixed and Mobile Platforms +* =initializeCylindricalPlatforms=: Initialize the geometry of the Fixed and Mobile Platforms :PROPERTIES: :header-args:matlab+: :tangle ../src/initializeCylindricalPlatforms.m :header-args:matlab+: :comments none :mkdirp yes :eval no :END: <> -This Matlab function is accessible [[file:src/initializeCylindricalPlatforms.m][here]]. +This Matlab function is accessible [[file:../src/initializeCylindricalPlatforms.m][here]]. -*** Function description +** Function description +:PROPERTIES: +:UNNUMBERED: t +:END: #+begin_src matlab function [stewart] = initializeCylindricalPlatforms(stewart, args) % initializeCylindricalPlatforms - Initialize the geometry of the Fixed and Mobile Platforms @@ -432,18 +538,23 @@ This Matlab function is accessible [[file:src/initializeCylindricalPlatforms.m][ % % Outputs: % - stewart - updated Stewart structure with the added fields: - % - platforms [struct] - structure with the following fields: - % - Fpm [1x1] - Fixed Platform Mass [kg] - % - Msi [3x3] - Mobile Platform Inertia matrix [kg*m^2] - % - Fph [1x1] - Fixed Platform Height [m] - % - Fpr [1x1] - Fixed Platform Radius [m] - % - Mpm [1x1] - Mobile Platform Mass [kg] - % - Fsi [3x3] - Fixed Platform Inertia matrix [kg*m^2] - % - Mph [1x1] - Mobile Platform Height [m] - % - Mpr [1x1] - Mobile Platform Radius [m] + % - 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 +** Optional Parameters +:PROPERTIES: +:UNNUMBERED: t +:END: #+begin_src matlab arguments stewart @@ -456,40 +567,57 @@ This Matlab function is accessible [[file:src/initializeCylindricalPlatforms.m][ end #+end_src -*** Create the =platforms= struct +** Compute the Inertia matrices of platforms +:PROPERTIES: +:UNNUMBERED: t +:END: #+begin_src matlab - platforms = struct(); - - platforms.Fpm = args.Fpm; - platforms.Fph = args.Fph; - platforms.Fpr = args.Fpr; - platforms.Fpi = diag([1/12 * platforms.Fpm * (3*platforms.Fpr^2 + platforms.Fph^2), ... - 1/12 * platforms.Fpm * (3*platforms.Fpr^2 + platforms.Fph^2), ... - 1/2 * platforms.Fpm * platforms.Fpr^2]); - - platforms.Mpm = args.Mpm; - platforms.Mph = args.Mph; - platforms.Mpr = args.Mpr; - platforms.Mpi = diag([1/12 * platforms.Mpm * (3*platforms.Mpr^2 + platforms.Mph^2), ... - 1/12 * platforms.Mpm * (3*platforms.Mpr^2 + platforms.Mph^2), ... - 1/2 * platforms.Mpm * platforms.Mpr^2]); + 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 -*** Save the =platforms= struct #+begin_src matlab - stewart.platforms = platforms; + 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 -** =initializeCylindricalStruts=: Define the mass and moment of inertia of cylindrical struts +** 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 ../src/initializeCylindricalStruts.m :header-args:matlab+: :comments none :mkdirp yes :eval no :END: <> -This Matlab function is accessible [[file:src/initializeCylindricalStruts.m][here]]. +This Matlab function is accessible [[file:../src/initializeCylindricalStruts.m][here]]. -*** Function description +** 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 @@ -507,18 +635,22 @@ This Matlab function is accessible [[file:src/initializeCylindricalStruts.m][her % % Outputs: % - stewart - updated Stewart structure with the added fields: - % - struts [struct] - structure with the following fields: - % - Fsm [6x1] - Mass of the Fixed part of the struts [kg] - % - Fsi [3x3x6] - Moment of Inertia for the Fixed part of the struts [kg*m^2] - % - Msm [6x1] - Mass of the Mobile part of the struts [kg] - % - Msi [3x3x6] - Moment of Inertia for the Mobile part of the struts [kg*m^2] - % - Fsh [6x1] - Height of cylinder for the Fixed part of the struts [m] - % - Fsr [6x1] - Radius of cylinder for the Fixed part of the struts [m] - % - Msh [6x1] - Height of cylinder for the Mobile part of the struts [m] - % - Msr [6x1] - Radius of cylinder for the Mobile part of the struts [m] + % - 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 +** Optional Parameters +:PROPERTIES: +:UNNUMBERED: t +:END: #+begin_src matlab arguments stewart @@ -531,74 +663,1222 @@ This Matlab function is accessible [[file:src/initializeCylindricalStruts.m][her end #+end_src -*** Create the =struts= structure +** Compute the properties of the cylindrical struts +:PROPERTIES: +:UNNUMBERED: t +:END: + #+begin_src matlab - struts = struct(); + Fsm = ones(6,1).*args.Fsm; + Fsh = ones(6,1).*args.Fsh; + Fsr = ones(6,1).*args.Fsr; - struts.Fsm = ones(6,1).*args.Fsm; - struts.Msm = ones(6,1).*args.Msm; + Msm = ones(6,1).*args.Msm; + Msh = ones(6,1).*args.Msh; + Msr = ones(6,1).*args.Msr; +#+end_src - struts.Fsh = ones(6,1).*args.Fsh; - struts.Fsr = ones(6,1).*args.Fsr; - struts.Msh = ones(6,1).*args.Msh; - struts.Msr = ones(6,1).*args.Msr; +#+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 - struts.Fsi = zeros(3, 3, 6); - struts.Msi = zeros(3, 3, 6); for i = 1:6 - struts.Fsi(:,:,i) = diag([1/12 * struts.Fsm(i) * (3*struts.Fsr(i)^2 + struts.Fsh(i)^2), ... - 1/12 * struts.Fsm(i) * (3*struts.Fsr(i)^2 + struts.Fsh(i)^2), ... - 1/2 * struts.Fsm(i) * struts.Fsr(i)^2]); - struts.Msi(:,:,i) = diag([1/12 * struts.Msm(i) * (3*struts.Msr(i)^2 + struts.Msh(i)^2), ... - 1/12 * struts.Msm(i) * (3*struts.Msr(i)^2 + struts.Msh(i)^2), ... - 1/2 * struts.Msm(i) * struts.Msr(i)^2]); + 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 = struts; + 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 -* Utility Functions -** =inverseKinematics=: Compute Inverse Kinematics +#+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 ../src/initializeStrutDynamics.m +:header-args:matlab+: :comments none :mkdirp yes :eval no +:END: +<> + +This Matlab function is accessible [[file:../src/initializeStrutDynamics.m][here]]. + +** 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 + \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.K (6,1) double {mustBeNumeric, mustBeNonnegative} = 20e6*ones(6,1) + args.C (6,1) double {mustBeNumeric, mustBeNonnegative} = 2e1*ones(6,1) + end +#+end_src + +** Add Stiffness and Damping properties of each strut +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + stewart.actuators.type = 1; + + stewart.actuators.K = args.K; + stewart.actuators.C = args.C; +#+end_src + +* =initializeAmplifiedStrutDynamics=: Add Stiffness and Damping properties of each strut for an amplified piezoelectric actuator +:PROPERTIES: +:header-args:matlab+: :tangle ../src/initializeAmplifiedStrutDynamics.m +:header-args:matlab+: :comments none :mkdirp yes :eval no +:END: +<> + +This Matlab function is accessible [[file:../src/initializeAmplifiedStrutDynamics.m][here]]. + +** Documentation +:PROPERTIES: +:UNNUMBERED: t +:END: + +An amplified piezoelectric actuator is shown in Figure [[fig:cedrat_apa95ml]]. + +#+name: fig:cedrat_apa95ml +#+attr_html: :width 500px +#+caption: Example of an Amplified piezoelectric actuator with an integrated displacement sensor (Cedrat Technologies) +[[file:figs/amplified_piezo_with_displacement_sensor.jpg]] + +A simplistic model of such amplified actuator is shown in Figure [[fig:amplified_piezo_model]] where: +- $K_{r}$ represent the vertical stiffness when the piezoelectric stack is removed +- $K_{a}$ is the vertical stiffness contribution of the piezoelectric stack +- $F_{i}$ represents the part of the piezoelectric stack that is used as a force actuator +- $F_{m,i}$ represents the remaining part of the piezoelectric stack that is used as a force sensor +- $v_{m,i}$ represents the absolute velocity of the top part of the actuator +- $d_{m,i}$ represents the total relative displacement of the actuator + +#+begin_src latex :file iff_1dof.pdf + \begin{tikzpicture} + % Ground + \draw (-1.2, 0) -- (1, 0); + + % Mass + \draw (-1.2, 1.4) -- ++(2.2, 0); + \node[forcesensor={0.4}{0.4}] (fsensn) at (0, 1){}; + \draw[] (-0.4, 1) -- (0.4, 1); + \node[right] at (fsensn.east) {$F_{m}$}; + + % Spring, Damper, and Actuator + \draw[spring] (-0.4, 0) -- (-0.4, 1) node[midway, right=0.1]{$K_{a}$}; + \draw[actuator={0.4}{0.2}] (0.4, 0) -- (0.4, 1) node[midway, right=0.1]{$F$}; + + \draw[spring] (-1, 0) -- (-1, 1.4) node[midway, left=0.1]{$K_{r}$}; + + \draw[dashed] (1, 0) -- ++(0.4, 0); + + \draw[dashed] (1, 1.4) -- ++(0.4, 0); + + \draw[->] (0, 1.4)node[]{$\bullet$} -- ++(0, 0.5) node[right]{$v_{m}$}; + + \draw[<->] (1.4, 0) -- ++(0, 1.4) node[midway, right]{$d_{m}$}; + \end{tikzpicture} +#+end_src + +#+name: fig:amplified_piezo_model +#+caption: Model of an amplified actuator +#+RESULTS: +[[file:figs/iff_1dof.png]] + +** Function description +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + function [stewart] = initializeAmplifiedStrutDynamics(stewart, args) + % initializeAmplifiedStrutDynamics - Add Stiffness and Damping properties of each strut + % + % Syntax: [stewart] = initializeAmplifiedStrutDynamics(args) + % + % Inputs: + % - args - Structure with the following fields: + % - Ka [6x1] - Vertical stiffness contribution of the piezoelectric stack [N/m] + % - Ca [6x1] - Vertical damping contribution of the piezoelectric stack [N/(m/s)] + % - Kr [6x1] - Vertical (residual) stiffness when the piezoelectric stack is removed [N/m] + % - Cr [6x1] - Vertical (residual) damping when the piezoelectric stack is removed [N/(m/s)] + % + % Outputs: + % - stewart - updated Stewart structure with the added fields: + % - actuators.type = 2 + % - actuators.K [6x1] - Total Stiffness of each strut [N/m] + % - actuators.C [6x1] - Total Damping of each strut [N/(m/s)] + % - actuators.Ka [6x1] - Vertical stiffness contribution of the piezoelectric stack [N/m] + % - actuators.Ca [6x1] - Vertical damping contribution of the piezoelectric stack [N/(m/s)] + % - actuators.Kr [6x1] - Vertical stiffness when the piezoelectric stack is removed [N/m] + % - actuators.Cr [6x1] - Vertical damping when the piezoelectric stack is removed [N/(m/s)] +#+end_src + +** Optional Parameters +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + arguments + stewart + args.Kr (6,1) double {mustBeNumeric, mustBeNonnegative} = 5e6*ones(6,1) + args.Cr (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e1*ones(6,1) + args.Ka (6,1) double {mustBeNumeric, mustBeNonnegative} = 15e6*ones(6,1) + args.Ca (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e1*ones(6,1) + end +#+end_src + +** Compute the total stiffness and damping +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + K = args.Ka + args.Kr; + C = args.Ca + args.Cr; +#+end_src + +** Populate the =stewart= structure +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + stewart.actuators.type = 2; + + stewart.actuators.Ka = args.Ka; + stewart.actuators.Ca = args.Ca; + + stewart.actuators.Kr = args.Kr; + stewart.actuators.Cr = args.Cr; + + stewart.actuators.K = K; + stewart.actuators.C = K; +#+end_src + +* =initializeJointDynamics=: Add Stiffness and Damping properties for spherical joints +:PROPERTIES: +:header-args:matlab+: :tangle ../src/initializeJointDynamics.m +:header-args:matlab+: :comments none :mkdirp yes :eval no +:END: +<> + +This Matlab function is accessible [[file:../src/initializeJointDynamics.m][here]]. + +** 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' + args.type_M char {mustBeMember(args.type_M,{'universal', 'spherical', 'universal_p', 'spherical_p'})} = 'spherical' + args.Kf_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 15*ones(6,1) + args.Cf_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-4*ones(6,1) + args.Kt_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 20*ones(6,1) + args.Ct_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-3*ones(6,1) + args.Kf_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 15*ones(6,1) + args.Cf_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-4*ones(6,1) + args.Kt_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 20*ones(6,1) + args.Ct_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-3*ones(6,1) + 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; + 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; + end +#+end_src + +** Add Stiffness and Damping in Translation of each strut +:PROPERTIES: +:UNNUMBERED: t +:END: +Translation Stiffness +#+begin_src matlab + stewart.joints_M.Kx = zeros(6,1); + stewart.joints_M.Ky = zeros(6,1); + stewart.joints_M.Kz = zeros(6,1); + + stewart.joints_F.Kx = zeros(6,1); + stewart.joints_F.Ky = zeros(6,1); + stewart.joints_F.Kz = zeros(6,1); +#+end_src + +Translation Damping +#+begin_src matlab + stewart.joints_M.Cx = zeros(6,1); + stewart.joints_M.Cy = zeros(6,1); + stewart.joints_M.Cz = zeros(6,1); + + stewart.joints_F.Cx = zeros(6,1); + stewart.joints_F.Cy = zeros(6,1); + stewart.joints_F.Cz = zeros(6,1); +#+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.Kf_M; + + stewart.joints_F.Kf = args.Kf_F; + stewart.joints_F.Kt = args.Kf_F; +#+end_src + + +Rotational Damping +#+begin_src matlab + stewart.joints_M.Cf = args.Cf_M; + stewart.joints_M.Ct = args.Cf_M; + + stewart.joints_F.Cf = args.Cf_F; + stewart.joints_F.Ct = args.Cf_F; +#+end_src + +* =initializeInertialSensor=: Initialize the inertial sensor in each strut +:PROPERTIES: +:header-args:matlab+: :tangle ../src/initializeInertialSensor.m +:header-args:matlab+: :comments none :mkdirp yes :eval no +:END: +<> + +This Matlab function is accessible [[file:../src/initializeInertialSensor.m][here]]. + +** 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 + +* =displayArchitecture=: 3D plot of the Stewart platform architecture +:PROPERTIES: +:header-args:matlab+: :tangle ../src/displayArchitecture.m +:header-args:matlab+: :comments none :mkdirp yes :eval no +:END: +<> + +This Matlab function is accessible [[file:../src/displayArchitecture.m][here]]. + +** Function description +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + function [] = displayArchitecture(stewart, args) + % displayArchitecture - 3D plot of the Stewart platform architecture + % + % Syntax: [] = displayArchitecture(args) + % + % Inputs: + % - stewart + % - args - Structure with 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} + % - ARB [3x3] - The rotation matrix that gives the wanted orientation of {B} with respect to {A} + % - F_color [color] - Color used for the Fixed elements + % - M_color [color] - Color used for the Mobile elements + % - L_color [color] - Color used for the Legs elements + % - frames [true/false] - Display the Frames + % - legs [true/false] - Display the Legs + % - joints [true/false] - Display the Joints + % - labels [true/false] - Display the Labels + % - platforms [true/false] - Display the Platforms + % - views ['all', 'xy', 'yz', 'xz', 'default'] - + % + % Outputs: +#+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) + args.F_color = [0 0.4470 0.7410] + args.M_color = [0.8500 0.3250 0.0980] + args.L_color = [0 0 0] + args.frames logical {mustBeNumericOrLogical} = true + args.legs logical {mustBeNumericOrLogical} = true + args.joints logical {mustBeNumericOrLogical} = true + args.labels logical {mustBeNumericOrLogical} = true + args.platforms logical {mustBeNumericOrLogical} = true + args.views char {mustBeMember(args.views,{'all', 'xy', 'xz', 'yz', 'default'})} = 'default' + end +#+end_src + +** Check the =stewart= structure elements +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + 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, 'H'), 'stewart.geometry should have attribute H') + H = stewart.geometry.H; + + 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; +#+end_src + + +** Figure Creation, Frames and Homogeneous transformations +:PROPERTIES: +:UNNUMBERED: t +:END: + +The reference frame of the 3d plot corresponds to the frame $\{F\}$. +#+begin_src matlab + if ~strcmp(args.views, 'all') + figure; + else + f = figure('visible', 'off'); + end + + hold on; +#+end_src + +We first compute homogeneous matrices that will be useful to position elements on the figure where the reference frame is $\{F\}$. +#+begin_src matlab + FTa = [eye(3), FO_A; ... + zeros(1,3), 1]; + ATb = [args.ARB, args.AP; ... + zeros(1,3), 1]; + BTm = [eye(3), -MO_B; ... + zeros(1,3), 1]; + + FTm = FTa*ATb*BTm; +#+end_src + +Let's define a parameter that define the length of the unit vectors used to display the frames. +#+begin_src matlab + d_unit_vector = H/4; +#+end_src + +Let's define a parameter used to position the labels with respect to the center of the element. +#+begin_src matlab + d_label = H/20; +#+end_src + +** Fixed Base elements +:PROPERTIES: +:UNNUMBERED: t +:END: +Let's first plot the frame $\{F\}$. +#+begin_src matlab + Ff = [0, 0, 0]; + if args.frames + quiver3(Ff(1)*ones(1,3), Ff(2)*ones(1,3), Ff(3)*ones(1,3), ... + [d_unit_vector 0 0], [0 d_unit_vector 0], [0 0 d_unit_vector], '-', 'Color', args.F_color) + + if args.labels + text(Ff(1) + d_label, ... + Ff(2) + d_label, ... + Ff(3) + d_label, '$\{F\}$', 'Color', args.F_color); + end + end +#+end_src + +Now plot the frame $\{A\}$ fixed to the Base. +#+begin_src matlab + if args.frames + quiver3(FO_A(1)*ones(1,3), FO_A(2)*ones(1,3), FO_A(3)*ones(1,3), ... + [d_unit_vector 0 0], [0 d_unit_vector 0], [0 0 d_unit_vector], '-', 'Color', args.F_color) + + if args.labels + text(FO_A(1) + d_label, ... + FO_A(2) + d_label, ... + FO_A(3) + d_label, '$\{A\}$', 'Color', args.F_color); + end + end +#+end_src + +Let's then plot the circle corresponding to the shape of the Fixed base. +#+begin_src matlab + if args.platforms && stewart.platform_F.type == 1 + theta = [0:0.01:2*pi+0.01]; % Angles [rad] + v = null([0; 0; 1]'); % Two vectors that are perpendicular to the circle normal + center = [0; 0; 0]; % Center of the circle + radius = stewart.platform_F.R; % Radius of the circle [m] + + points = center*ones(1, length(theta)) + radius*(v(:,1)*cos(theta) + v(:,2)*sin(theta)); + + plot3(points(1,:), ... + points(2,:), ... + points(3,:), '-', 'Color', args.F_color); + end +#+end_src + +Let's now plot the position and labels of the Fixed Joints +#+begin_src matlab + if args.joints + scatter3(Fa(1,:), ... + Fa(2,:), ... + Fa(3,:), 'MarkerEdgeColor', args.F_color); + if args.labels + for i = 1:size(Fa,2) + text(Fa(1,i) + d_label, ... + Fa(2,i), ... + Fa(3,i), sprintf('$a_{%i}$', i), 'Color', args.F_color); + end + end + end +#+end_src + +** Mobile Platform elements +:PROPERTIES: +:UNNUMBERED: t +:END: + +Plot the frame $\{M\}$. +#+begin_src matlab + Fm = FTm*[0; 0; 0; 1]; % Get the position of frame {M} w.r.t. {F} + + if args.frames + FM_uv = FTm*[d_unit_vector*eye(3); zeros(1,3)]; % Rotated Unit vectors + quiver3(Fm(1)*ones(1,3), Fm(2)*ones(1,3), Fm(3)*ones(1,3), ... + FM_uv(1,1:3), FM_uv(2,1:3), FM_uv(3,1:3), '-', 'Color', args.M_color) + + if args.labels + text(Fm(1) + d_label, ... + Fm(2) + d_label, ... + Fm(3) + d_label, '$\{M\}$', 'Color', args.M_color); + end + end +#+end_src + +Plot the frame $\{B\}$. +#+begin_src matlab + FB = FO_A + args.AP; + + if args.frames + FB_uv = FTm*[d_unit_vector*eye(3); zeros(1,3)]; % Rotated Unit vectors + quiver3(FB(1)*ones(1,3), FB(2)*ones(1,3), FB(3)*ones(1,3), ... + FB_uv(1,1:3), FB_uv(2,1:3), FB_uv(3,1:3), '-', 'Color', args.M_color) + + if args.labels + text(FB(1) - d_label, ... + FB(2) + d_label, ... + FB(3) + d_label, '$\{B\}$', 'Color', args.M_color); + end + end +#+end_src + +Let's then plot the circle corresponding to the shape of the Mobile platform. +#+begin_src matlab + if args.platforms && stewart.platform_M.type == 1 + theta = [0:0.01:2*pi+0.01]; % Angles [rad] + v = null((FTm(1:3,1:3)*[0;0;1])'); % Two vectors that are perpendicular to the circle normal + center = Fm(1:3); % Center of the circle + radius = stewart.platform_M.R; % Radius of the circle [m] + + points = center*ones(1, length(theta)) + radius*(v(:,1)*cos(theta) + v(:,2)*sin(theta)); + + plot3(points(1,:), ... + points(2,:), ... + points(3,:), '-', 'Color', args.M_color); + end +#+end_src + +Plot the position and labels of the rotation joints fixed to the mobile platform. +#+begin_src matlab + if args.joints + Fb = FTm*[Mb;ones(1,6)]; + + scatter3(Fb(1,:), ... + Fb(2,:), ... + Fb(3,:), 'MarkerEdgeColor', args.M_color); + + if args.labels + for i = 1:size(Fb,2) + text(Fb(1,i) + d_label, ... + Fb(2,i), ... + Fb(3,i), sprintf('$b_{%i}$', i), 'Color', args.M_color); + end + end + end +#+end_src + +** Legs +:PROPERTIES: +:UNNUMBERED: t +:END: +Plot the legs connecting the joints of the fixed base to the joints of the mobile platform. +#+begin_src matlab + if args.legs + for i = 1:6 + plot3([Fa(1,i), Fb(1,i)], ... + [Fa(2,i), Fb(2,i)], ... + [Fa(3,i), Fb(3,i)], '-', 'Color', args.L_color); + + if args.labels + text((Fa(1,i)+Fb(1,i))/2 + d_label, ... + (Fa(2,i)+Fb(2,i))/2, ... + (Fa(3,i)+Fb(3,i))/2, sprintf('$%i$', i), 'Color', args.L_color); + end + end + end +#+end_src + +** Figure parameters +#+begin_src matlab + switch args.views + case 'default' + view([1 -0.6 0.4]); + case 'xy' + view([0 0 1]); + case 'xz' + view([0 -1 0]); + case 'yz' + view([1 0 0]); + end + axis equal; + axis off; +#+end_src + +** Subplots +#+begin_src matlab + if strcmp(args.views, 'all') + hAx = findobj('type', 'axes'); + + figure; + s1 = subplot(2,2,1); + copyobj(get(hAx(1), 'Children'), s1); + view([0 0 1]); + axis equal; + axis off; + title('Top') + + s2 = subplot(2,2,2); + copyobj(get(hAx(1), 'Children'), s2); + view([1 -0.6 0.4]); + axis equal; + axis off; + + s3 = subplot(2,2,3); + copyobj(get(hAx(1), 'Children'), s3); + view([1 0 0]); + axis equal; + axis off; + title('Front') + + s4 = subplot(2,2,4); + copyobj(get(hAx(1), 'Children'), s4); + view([0 -1 0]); + axis equal; + axis off; + title('Side') + + close(f); + end +#+end_src + + +* =describeStewartPlatform=: Display some text describing the current defined Stewart Platform +:PROPERTIES: +:header-args:matlab+: :tangle ../src/describeStewartPlatform.m +:header-args:matlab+: :comments none :mkdirp yes :eval no +:END: +<> + +This Matlab function is accessible [[file:../src/describeStewartPlatform.m][here]]. + +** Function description +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + function [] = describeStewartPlatform(stewart) + % describeStewartPlatform - Display some text describing the current defined Stewart Platform + % + % Syntax: [] = describeStewartPlatform(args) + % + % Inputs: + % - stewart + % + % Outputs: +#+end_src + +** Optional Parameters +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + arguments + stewart + end +#+end_src + +** Geometry +#+begin_src matlab + fprintf('GEOMETRY:\n') + fprintf('- The height between the fixed based and the top platform is %.3g [mm].\n', 1e3*stewart.geometry.H) + + if stewart.platform_M.MO_B(3) > 0 + fprintf('- Frame {A} is located %.3g [mm] above the top platform.\n', 1e3*stewart.platform_M.MO_B(3)) + else + fprintf('- Frame {A} is located %.3g [mm] below the top platform.\n', - 1e3*stewart.platform_M.MO_B(3)) + end + + fprintf('- The initial length of the struts are:\n') + fprintf('\t %.3g, %.3g, %.3g, %.3g, %.3g, %.3g [mm]\n', 1e3*stewart.geometry.l) + fprintf('\n') +#+end_src + +** Actuators +#+begin_src matlab + fprintf('ACTUATORS:\n') + if stewart.actuators.type == 1 + fprintf('- The actuators are classical.\n') + fprintf('- The Stiffness and Damping of each actuators is:\n') + fprintf('\t k = %.0e [N/m] \t c = %.0e [N/(m/s)]\n', stewart.actuators.K(1), stewart.actuators.C(1)) + elseif stewart.actuators.type == 2 + fprintf('- The actuators are mechanicaly amplified.\n') + fprintf('- The vertical stiffness and damping contribution of the piezoelectric stack is:\n') + fprintf('\t ka = %.0e [N/m] \t ca = %.0e [N/(m/s)]\n', stewart.actuators.Ka(1), stewart.actuators.Ca(1)) + fprintf('- Vertical stiffness when the piezoelectric stack is removed is:\n') + fprintf('\t kr = %.0e [N/m] \t cr = %.0e [N/(m/s)]\n', stewart.actuators.Kr(1), stewart.actuators.Cr(1)) + end + fprintf('\n') +#+end_src + +** Joints +#+begin_src matlab + fprintf('JOINTS:\n') +#+end_src + +Type of the joints on the fixed base. +#+begin_src matlab + switch stewart.joints_F.type + case 1 + fprintf('- The joints on the fixed based are universal joints\n') + case 2 + fprintf('- The joints on the fixed based are spherical joints\n') + case 3 + fprintf('- The joints on the fixed based are perfect universal joints\n') + case 4 + fprintf('- The joints on the fixed based are perfect spherical joints\n') + end +#+end_src + +Type of the joints on the mobile platform. +#+begin_src matlab + switch stewart.joints_M.type + case 1 + fprintf('- The joints on the mobile based are universal joints\n') + case 2 + fprintf('- The joints on the mobile based are spherical joints\n') + case 3 + fprintf('- The joints on the mobile based are perfect universal joints\n') + case 4 + fprintf('- The joints on the mobile based are perfect spherical joints\n') + end +#+end_src + +Position of the fixed joints +#+begin_src matlab + fprintf('- The position of the joints on the fixed based with respect to {F} are (in [mm]):\n') + fprintf('\t % .3g \t % .3g \t % .3g\n', 1e3*stewart.platform_F.Fa) +#+end_src + +Position of the mobile joints +#+begin_src matlab + fprintf('- The position of the joints on the mobile based with respect to {M} are (in [mm]):\n') + fprintf('\t % .3g \t % .3g \t % .3g\n', 1e3*stewart.platform_M.Mb) + fprintf('\n') +#+end_src + +** Kinematics +#+begin_src matlab + fprintf('KINEMATICS:\n') + + if isfield(stewart.kinematics, 'K') + fprintf('- The Stiffness matrix K is (in [N/m]):\n') + fprintf('\t % .0e \t % .0e \t % .0e \t % .0e \t % .0e \t % .0e\n', stewart.kinematics.K) + end + + if isfield(stewart.kinematics, 'C') + fprintf('- The Damping matrix C is (in [m/N]):\n') + fprintf('\t % .0e \t % .0e \t % .0e \t % .0e \t % .0e \t % .0e\n', stewart.kinematics.C) + end +#+end_src + +* =generateCubicConfiguration=: Generate a Cubic Configuration +:PROPERTIES: +:header-args:matlab+: :tangle ../src/generateCubicConfiguration.m +:header-args:matlab+: :comments none :mkdirp yes :eval no +:END: +<> + +This Matlab function is accessible [[file:../src/generateCubicConfiguration.m][here]]. + +** Function description +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + function [stewart] = generateCubicConfiguration(stewart, args) + % generateCubicConfiguration - Generate a Cubic Configuration + % + % Syntax: [stewart] = generateCubicConfiguration(stewart, args) + % + % Inputs: + % - stewart - A structure with the following fields + % - geometry.H [1x1] - Total height of the platform [m] + % - args - Can have the following fields: + % - Hc [1x1] - Height of the "useful" part of the cube [m] + % - FOc [1x1] - Height of the center of the cube with respect to {F} [m] + % - FHa [1x1] - Height of the plane joining the points ai with respect to the frame {F} [m] + % - MHb [1x1] - Height of the plane joining the points bi with respect to the frame {M} [m] + % + % 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 + +** Documentation +:PROPERTIES: +:UNNUMBERED: t +:END: +#+name: fig:cubic-configuration-definition +#+caption: Cubic Configuration +[[file:figs/cubic-configuration-definition.png]] + +** Optional Parameters +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + arguments + stewart + args.Hc (1,1) double {mustBeNumeric, mustBePositive} = 60e-3 + args.FOc (1,1) double {mustBeNumeric} = 50e-3 + args.FHa (1,1) double {mustBeNumeric, mustBeNonnegative} = 15e-3 + args.MHb (1,1) double {mustBeNumeric, mustBeNonnegative} = 15e-3 + end +#+end_src + +** Check the =stewart= structure elements +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + assert(isfield(stewart.geometry, 'H'), 'stewart.geometry should have attribute H') + H = stewart.geometry.H; +#+end_src + +** Position of the Cube +:PROPERTIES: +:UNNUMBERED: t +:END: +We define the useful points of the cube with respect to the Cube's center. +${}^{C}C$ are the 6 vertices of the cubes expressed in a frame {C} which is located at the center of the cube and aligned with {F} and {M}. + +#+begin_src matlab + sx = [ 2; -1; -1]; + sy = [ 0; 1; -1]; + sz = [ 1; 1; 1]; + + R = [sx, sy, sz]./vecnorm([sx, sy, sz]); + + L = args.Hc*sqrt(3); + + Cc = R'*[[0;0;L],[L;0;L],[L;0;0],[L;L;0],[0;L;0],[0;L;L]] - [0;0;1.5*args.Hc]; + + CCf = [Cc(:,1), Cc(:,3), Cc(:,3), Cc(:,5), Cc(:,5), Cc(:,1)]; % CCf(:,i) corresponds to the bottom cube's vertice corresponding to the i'th leg + CCm = [Cc(:,2), Cc(:,2), Cc(:,4), Cc(:,4), Cc(:,6), Cc(:,6)]; % CCm(:,i) corresponds to the top cube's vertice corresponding to the i'th leg +#+end_src + +** Compute the pose +:PROPERTIES: +:UNNUMBERED: t +:END: +We can compute the vector of each leg ${}^{C}\hat{\bm{s}}_{i}$ (unit vector from ${}^{C}C_{f}$ to ${}^{C}C_{m}$). +#+begin_src matlab + CSi = (CCm - CCf)./vecnorm(CCm - CCf); +#+end_src + +We now which to compute the position of the joints $a_{i}$ and $b_{i}$. +#+begin_src matlab + Fa = CCf + [0; 0; args.FOc] + ((args.FHa-(args.FOc-args.Hc/2))./CSi(3,:)).*CSi; + Mb = CCf + [0; 0; args.FOc-H] + ((H-args.MHb-(args.FOc-args.Hc/2))./CSi(3,:)).*CSi; +#+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 + +* =computeJacobian=: Compute the Jacobian Matrix +:PROPERTIES: +:header-args:matlab+: :tangle ../src/computeJacobian.m +:header-args:matlab+: :comments none :mkdirp yes :eval no +:END: +<> + +This Matlab function is accessible [[file:../src/computeJacobian.m][here]]. + +** 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 + + +* =inverseKinematics=: Compute Inverse Kinematics :PROPERTIES: :header-args:matlab+: :tangle ../src/inverseKinematics.m :header-args:matlab+: :comments none :mkdirp yes :eval no :END: <> -This Matlab function is accessible [[file:src/inverseKinematics.m][here]]. +This Matlab function is accessible [[file:../src/inverseKinematics.m][here]]. -*** Function description -#+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 - % - 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: - % - 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 -#+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 - -*** Theory +** 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 @@ -620,25 +1900,83 @@ Hence, for $i = 1, 2, \dots, 6$, each limb length can be uniquely determined by: 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. -*** Compute +** Function description +:PROPERTIES: +:UNNUMBERED: t +:END: #+begin_src matlab - Li = sqrt(args.AP'*args.AP + diag(stewart.Bb'*stewart.Bb) + diag(stewart.Aa'*stewart.Aa) - (2*args.AP'*stewart.Aa)' + (2*args.AP'*(args.ARB*stewart.Bb))' - diag(2*(args.ARB*stewart.Bb)'*stewart.Aa)); + 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-stewart.l; + dLi = Li-l; #+end_src -** =forwardKinematicsApprox=: Compute the Forward Kinematics +* =forwardKinematicsApprox=: Compute the Approximate Forward Kinematics :PROPERTIES: :header-args:matlab+: :tangle ../src/forwardKinematicsApprox.m :header-args:matlab+: :comments none :mkdirp yes :eval no :END: <> -This Matlab function is accessible [[file:src/forwardKinematicsApprox.m][here]]. +This Matlab function is accessible [[file:../src/forwardKinematicsApprox.m][here]]. -*** Function description +** Function description +:PROPERTIES: +:UNNUMBERED: t +:END: #+begin_src matlab function [P, R] = forwardKinematicsApprox(stewart, args) % forwardKinematicsApprox - Computed the approximate pose of {B} with respect to {A} from the length of each strut and using @@ -648,7 +1986,7 @@ This Matlab function is accessible [[file:src/forwardKinematicsApprox.m][here]]. % % Inputs: % - stewart - A structure with the following fields - % - J [6x6] - The Jacobian Matrix + % - kinematics.J [6x6] - The Jacobian Matrix % - args - Can have the following fields: % - dL [6x1] - Displacement of each strut [m] % @@ -657,7 +1995,10 @@ This Matlab function is accessible [[file:src/forwardKinematicsApprox.m][here]]. % - R [3x3] - The estimated rotation matrix that gives the orientation of {B} with respect to {A} #+end_src -*** Optional Parameters +** Optional Parameters +:PROPERTIES: +:UNNUMBERED: t +:END: #+begin_src matlab arguments stewart @@ -665,12 +2006,24 @@ This Matlab function is accessible [[file:src/forwardKinematicsApprox.m][here]]. end #+end_src -*** Computation +** Check the =stewart= structure elements +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + assert(isfield(stewart.kinematics, 'J'), 'stewart.kinematics should have attribute J') + J = stewart.kinematics.J; +#+end_src + +** Computation +:PROPERTIES: +:UNNUMBERED: t +:END: From a small displacement of each strut $d\bm{\mathcal{L}}$, we can compute the position and orientation of {B} with respect to {A} using the following formula: \[ d \bm{\mathcal{X}} = \bm{J}^{-1} d\bm{\mathcal{L}} \] #+begin_src matlab - X = stewart.J\args.dL; + X = J\args.dL; #+end_src The position vector corresponds to the first 3 elements. diff --git a/src/computeJacobian.m b/src/computeJacobian.m index 80200a0..e4a37a8 100644 --- a/src/computeJacobian.m +++ b/src/computeJacobian.m @@ -5,17 +5,31 @@ function [stewart] = computeJacobian(stewart) % % Inputs: % - stewart - With at least the following fields: -% - As [3x6] - The 6 unit vectors for each strut expressed in {A} -% - Ab [3x6] - The 6 position of the joints bi expressed in {A} +% - 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: -% - J [6x6] - The Jacobian Matrix -% - K [6x6] - The Stiffness Matrix -% - C [6x6] - The Compliance Matrix +% - kinematics.J [6x6] - The Jacobian Matrix +% - kinematics.K [6x6] - The Stiffness Matrix +% - kinematics.C [6x6] - The Compliance Matrix -stewart.J = [stewart.As' , cross(stewart.Ab, stewart.As)']; +assert(isfield(stewart.geometry, 'As'), 'stewart.geometry should have attribute As') +As = stewart.geometry.As; -stewart.K = stewart.J'*diag(stewart.Ki)*stewart.J; +assert(isfield(stewart.geometry, 'Ab'), 'stewart.geometry should have attribute Ab') +Ab = stewart.geometry.Ab; -stewart.C = inv(stewart.K); +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/src/computeJointsPose.m b/src/computeJointsPose.m index 5b5754e..3e31760 100644 --- a/src/computeJointsPose.m +++ b/src/computeJointsPose.m @@ -5,43 +5,74 @@ function [stewart] = computeJointsPose(stewart) % % Inputs: % - stewart - A structure with the following fields -% - Fa [3x6] - Its i'th column is the position vector of joint ai with respect to {F} -% - Mb [3x6] - Its i'th column is the position vector of joint bi with respect to {M} -% - FO_A [3x1] - Position of {A} with respect to {F} -% - MO_B [3x1] - Position of {B} with respect to {M} -% - FO_M [3x1] - Position of {M} with respect to {F} +% - 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 -% - Aa [3x6] - The i'th column is the position of ai with respect to {A} -% - Ab [3x6] - The i'th column is the position of bi with respect to {A} -% - Ba [3x6] - The i'th column is the position of ai with respect to {B} -% - Bb [3x6] - The i'th column is the position of bi with respect to {B} -% - l [6x1] - The i'th element is the initial length of strut i -% - As [3x6] - The i'th column is the unit vector of strut i expressed in {A} -% - Bs [3x6] - The i'th column is the unit vector of strut i expressed in {B} -% - FRa [3x3x6] - The i'th 3x3 array is the rotation matrix to orientate the bottom of the i'th strut from {F} -% - MRb [3x3x6] - The i'th 3x3 array is the rotation matrix to orientate the top of the i'th strut from {M} +% - 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} -stewart.Aa = stewart.Fa - repmat(stewart.FO_A, [1, 6]); -stewart.Bb = stewart.Mb - repmat(stewart.MO_B, [1, 6]); +assert(isfield(stewart.platform_F, 'Fa'), 'stewart.platform_F should have attribute Fa') +Fa = stewart.platform_F.Fa; -stewart.Ab = stewart.Bb - repmat(-stewart.MO_B-stewart.FO_M+stewart.FO_A, [1, 6]); -stewart.Ba = stewart.Aa - repmat( stewart.MO_B+stewart.FO_M-stewart.FO_A, [1, 6]); +assert(isfield(stewart.platform_M, 'Mb'), 'stewart.platform_M should have attribute Mb') +Mb = stewart.platform_M.Mb; -stewart.As = (stewart.Ab - stewart.Aa)./vecnorm(stewart.Ab - stewart.Aa); % As_i is the i'th vector of As +assert(isfield(stewart.platform_F, 'FO_A'), 'stewart.platform_F should have attribute FO_A') +FO_A = stewart.platform_F.FO_A; -stewart.l = vecnorm(stewart.Ab - stewart.Aa)'; +assert(isfield(stewart.platform_M, 'MO_B'), 'stewart.platform_M should have attribute MO_B') +MO_B = stewart.platform_M.MO_B; -stewart.Bs = (stewart.Bb - stewart.Ba)./vecnorm(stewart.Bb - stewart.Ba); +assert(isfield(stewart.geometry, 'FO_M'), 'stewart.geometry should have attribute FO_M') +FO_M = stewart.geometry.FO_M; -stewart.FRa = zeros(3,3,6); -stewart.MRb = zeros(3,3,6); +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 - stewart.FRa(:,:,i) = [cross([0;1;0], stewart.As(:,i)) , cross(stewart.As(:,i), cross([0;1;0], stewart.As(:,i))) , stewart.As(:,i)]; - stewart.FRa(:,:,i) = stewart.FRa(:,:,i)./vecnorm(stewart.FRa(:,:,i)); + 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)); - stewart.MRb(:,:,i) = [cross([0;1;0], stewart.Bs(:,i)) , cross(stewart.Bs(:,i), cross([0;1;0], stewart.Bs(:,i))) , stewart.Bs(:,i)]; - stewart.MRb(:,:,i) = stewart.MRb(:,:,i)./vecnorm(stewart.MRb(:,:,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/src/describeStewartPlatform.m b/src/describeStewartPlatform.m new file mode 100644 index 0000000..256fc60 --- /dev/null +++ b/src/describeStewartPlatform.m @@ -0,0 +1,83 @@ +function [] = describeStewartPlatform(stewart) +% describeStewartPlatform - Display some text describing the current defined Stewart Platform +% +% Syntax: [] = describeStewartPlatform(args) +% +% Inputs: +% - stewart +% +% Outputs: + +arguments + stewart +end + +fprintf('GEOMETRY:\n') +fprintf('- The height between the fixed based and the top platform is %.3g [mm].\n', 1e3*stewart.geometry.H) + +if stewart.platform_M.MO_B(3) > 0 + fprintf('- Frame {A} is located %.3g [mm] above the top platform.\n', 1e3*stewart.platform_M.MO_B(3)) +else + fprintf('- Frame {A} is located %.3g [mm] below the top platform.\n', - 1e3*stewart.platform_M.MO_B(3)) +end + +fprintf('- The initial length of the struts are:\n') +fprintf('\t %.3g, %.3g, %.3g, %.3g, %.3g, %.3g [mm]\n', 1e3*stewart.geometry.l) +fprintf('\n') + +fprintf('ACTUATORS:\n') +if stewart.actuators.type == 1 + fprintf('- The actuators are classical.\n') + fprintf('- The Stiffness and Damping of each actuators is:\n') + fprintf('\t k = %.0e [N/m] \t c = %.0e [N/(m/s)]\n', stewart.actuators.K(1), stewart.actuators.C(1)) +elseif stewart.actuators.type == 2 + fprintf('- The actuators are mechanicaly amplified.\n') + fprintf('- The vertical stiffness and damping contribution of the piezoelectric stack is:\n') + fprintf('\t ka = %.0e [N/m] \t ca = %.0e [N/(m/s)]\n', stewart.actuators.Ka(1), stewart.actuators.Ca(1)) + fprintf('- Vertical stiffness when the piezoelectric stack is removed is:\n') + fprintf('\t kr = %.0e [N/m] \t cr = %.0e [N/(m/s)]\n', stewart.actuators.Kr(1), stewart.actuators.Cr(1)) +end +fprintf('\n') + +fprintf('JOINTS:\n') + +switch stewart.joints_F.type + case 1 + fprintf('- The joints on the fixed based are universal joints\n') + case 2 + fprintf('- The joints on the fixed based are spherical joints\n') + case 3 + fprintf('- The joints on the fixed based are perfect universal joints\n') + case 4 + fprintf('- The joints on the fixed based are perfect spherical joints\n') +end + +switch stewart.joints_M.type + case 1 + fprintf('- The joints on the mobile based are universal joints\n') + case 2 + fprintf('- The joints on the mobile based are spherical joints\n') + case 3 + fprintf('- The joints on the mobile based are perfect universal joints\n') + case 4 + fprintf('- The joints on the mobile based are perfect spherical joints\n') +end + +fprintf('- The position of the joints on the fixed based with respect to {F} are (in [mm]):\n') +fprintf('\t % .3g \t % .3g \t % .3g\n', 1e3*stewart.platform_F.Fa) + +fprintf('- The position of the joints on the mobile based with respect to {M} are (in [mm]):\n') +fprintf('\t % .3g \t % .3g \t % .3g\n', 1e3*stewart.platform_M.Mb) +fprintf('\n') + +fprintf('KINEMATICS:\n') + +if isfield(stewart.kinematics, 'K') + fprintf('- The Stiffness matrix K is (in [N/m]):\n') + fprintf('\t % .0e \t % .0e \t % .0e \t % .0e \t % .0e \t % .0e\n', stewart.kinematics.K) +end + +if isfield(stewart.kinematics, 'C') + fprintf('- The Damping matrix C is (in [m/N]):\n') + fprintf('\t % .0e \t % .0e \t % .0e \t % .0e \t % .0e \t % .0e\n', stewart.kinematics.C) +end diff --git a/src/displayArchitecture.m b/src/displayArchitecture.m new file mode 100644 index 0000000..2513217 --- /dev/null +++ b/src/displayArchitecture.m @@ -0,0 +1,240 @@ +function [] = displayArchitecture(stewart, args) +% displayArchitecture - 3D plot of the Stewart platform architecture +% +% Syntax: [] = displayArchitecture(args) +% +% Inputs: +% - stewart +% - args - Structure with 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} +% - ARB [3x3] - The rotation matrix that gives the wanted orientation of {B} with respect to {A} +% - F_color [color] - Color used for the Fixed elements +% - M_color [color] - Color used for the Mobile elements +% - L_color [color] - Color used for the Legs elements +% - frames [true/false] - Display the Frames +% - legs [true/false] - Display the Legs +% - joints [true/false] - Display the Joints +% - labels [true/false] - Display the Labels +% - platforms [true/false] - Display the Platforms +% - views ['all', 'xy', 'yz', 'xz', 'default'] - +% +% Outputs: + +arguments + stewart + args.AP (3,1) double {mustBeNumeric} = zeros(3,1) + args.ARB (3,3) double {mustBeNumeric} = eye(3) + args.F_color = [0 0.4470 0.7410] + args.M_color = [0.8500 0.3250 0.0980] + args.L_color = [0 0 0] + args.frames logical {mustBeNumericOrLogical} = true + args.legs logical {mustBeNumericOrLogical} = true + args.joints logical {mustBeNumericOrLogical} = true + args.labels logical {mustBeNumericOrLogical} = true + args.platforms logical {mustBeNumericOrLogical} = true + args.views char {mustBeMember(args.views,{'all', 'xy', 'xz', 'yz', 'default'})} = 'default' +end + +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, 'H'), 'stewart.geometry should have attribute H') +H = stewart.geometry.H; + +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; + +if ~strcmp(args.views, 'all') + figure; +else + f = figure('visible', 'off'); +end + +hold on; + +FTa = [eye(3), FO_A; ... + zeros(1,3), 1]; +ATb = [args.ARB, args.AP; ... + zeros(1,3), 1]; +BTm = [eye(3), -MO_B; ... + zeros(1,3), 1]; + +FTm = FTa*ATb*BTm; + +d_unit_vector = H/4; + +d_label = H/20; + +Ff = [0, 0, 0]; +if args.frames + quiver3(Ff(1)*ones(1,3), Ff(2)*ones(1,3), Ff(3)*ones(1,3), ... + [d_unit_vector 0 0], [0 d_unit_vector 0], [0 0 d_unit_vector], '-', 'Color', args.F_color) + + if args.labels + text(Ff(1) + d_label, ... + Ff(2) + d_label, ... + Ff(3) + d_label, '$\{F\}$', 'Color', args.F_color); + end +end + +if args.frames + quiver3(FO_A(1)*ones(1,3), FO_A(2)*ones(1,3), FO_A(3)*ones(1,3), ... + [d_unit_vector 0 0], [0 d_unit_vector 0], [0 0 d_unit_vector], '-', 'Color', args.F_color) + + if args.labels + text(FO_A(1) + d_label, ... + FO_A(2) + d_label, ... + FO_A(3) + d_label, '$\{A\}$', 'Color', args.F_color); + end +end + +if args.platforms && stewart.platform_F.type == 1 + theta = [0:0.01:2*pi+0.01]; % Angles [rad] + v = null([0; 0; 1]'); % Two vectors that are perpendicular to the circle normal + center = [0; 0; 0]; % Center of the circle + radius = stewart.platform_F.R; % Radius of the circle [m] + + points = center*ones(1, length(theta)) + radius*(v(:,1)*cos(theta) + v(:,2)*sin(theta)); + + plot3(points(1,:), ... + points(2,:), ... + points(3,:), '-', 'Color', args.F_color); +end + +if args.joints + scatter3(Fa(1,:), ... + Fa(2,:), ... + Fa(3,:), 'MarkerEdgeColor', args.F_color); + if args.labels + for i = 1:size(Fa,2) + text(Fa(1,i) + d_label, ... + Fa(2,i), ... + Fa(3,i), sprintf('$a_{%i}$', i), 'Color', args.F_color); + end + end +end + +Fm = FTm*[0; 0; 0; 1]; % Get the position of frame {M} w.r.t. {F} + +if args.frames + FM_uv = FTm*[d_unit_vector*eye(3); zeros(1,3)]; % Rotated Unit vectors + quiver3(Fm(1)*ones(1,3), Fm(2)*ones(1,3), Fm(3)*ones(1,3), ... + FM_uv(1,1:3), FM_uv(2,1:3), FM_uv(3,1:3), '-', 'Color', args.M_color) + + if args.labels + text(Fm(1) + d_label, ... + Fm(2) + d_label, ... + Fm(3) + d_label, '$\{M\}$', 'Color', args.M_color); + end +end + +FB = FO_A + args.AP; + +if args.frames + FB_uv = FTm*[d_unit_vector*eye(3); zeros(1,3)]; % Rotated Unit vectors + quiver3(FB(1)*ones(1,3), FB(2)*ones(1,3), FB(3)*ones(1,3), ... + FB_uv(1,1:3), FB_uv(2,1:3), FB_uv(3,1:3), '-', 'Color', args.M_color) + + if args.labels + text(FB(1) - d_label, ... + FB(2) + d_label, ... + FB(3) + d_label, '$\{B\}$', 'Color', args.M_color); + end +end + +if args.platforms && stewart.platform_M.type == 1 + theta = [0:0.01:2*pi+0.01]; % Angles [rad] + v = null((FTm(1:3,1:3)*[0;0;1])'); % Two vectors that are perpendicular to the circle normal + center = Fm(1:3); % Center of the circle + radius = stewart.platform_M.R; % Radius of the circle [m] + + points = center*ones(1, length(theta)) + radius*(v(:,1)*cos(theta) + v(:,2)*sin(theta)); + + plot3(points(1,:), ... + points(2,:), ... + points(3,:), '-', 'Color', args.M_color); +end + +if args.joints + Fb = FTm*[Mb;ones(1,6)]; + + scatter3(Fb(1,:), ... + Fb(2,:), ... + Fb(3,:), 'MarkerEdgeColor', args.M_color); + + if args.labels + for i = 1:size(Fb,2) + text(Fb(1,i) + d_label, ... + Fb(2,i), ... + Fb(3,i), sprintf('$b_{%i}$', i), 'Color', args.M_color); + end + end +end + +if args.legs + for i = 1:6 + plot3([Fa(1,i), Fb(1,i)], ... + [Fa(2,i), Fb(2,i)], ... + [Fa(3,i), Fb(3,i)], '-', 'Color', args.L_color); + + if args.labels + text((Fa(1,i)+Fb(1,i))/2 + d_label, ... + (Fa(2,i)+Fb(2,i))/2, ... + (Fa(3,i)+Fb(3,i))/2, sprintf('$%i$', i), 'Color', args.L_color); + end + end +end + +switch args.views + case 'default' + view([1 -0.6 0.4]); + case 'xy' + view([0 0 1]); + case 'xz' + view([0 -1 0]); + case 'yz' + view([1 0 0]); +end +axis equal; +axis off; + +if strcmp(args.views, 'all') + hAx = findobj('type', 'axes'); + + figure; + s1 = subplot(2,2,1); + copyobj(get(hAx(1), 'Children'), s1); + view([0 0 1]); + axis equal; + axis off; + title('Top') + + s2 = subplot(2,2,2); + copyobj(get(hAx(1), 'Children'), s2); + view([1 -0.6 0.4]); + axis equal; + axis off; + + s3 = subplot(2,2,3); + copyobj(get(hAx(1), 'Children'), s3); + view([1 0 0]); + axis equal; + axis off; + title('Front') + + s4 = subplot(2,2,4); + copyobj(get(hAx(1), 'Children'), s4); + view([0 -1 0]); + axis equal; + axis off; + title('Side') + + close(f); +end diff --git a/src/forwardKinematicsApprox.m b/src/forwardKinematicsApprox.m index 942b92a..a6f3c23 100644 --- a/src/forwardKinematicsApprox.m +++ b/src/forwardKinematicsApprox.m @@ -6,7 +6,7 @@ function [P, R] = forwardKinematicsApprox(stewart, args) % % Inputs: % - stewart - A structure with the following fields -% - J [6x6] - The Jacobian Matrix +% - kinematics.J [6x6] - The Jacobian Matrix % - args - Can have the following fields: % - dL [6x1] - Displacement of each strut [m] % @@ -19,7 +19,10 @@ arguments args.dL (6,1) double {mustBeNumeric} = zeros(6,1) end -X = stewart.J\args.dL; +assert(isfield(stewart.kinematics, 'J'), 'stewart.kinematics should have attribute J') +J = stewart.kinematics.J; + +X = J\args.dL; P = X(1:3); diff --git a/src/generateCubicConfiguration.m b/src/generateCubicConfiguration.m index 8bc48dc..596787b 100644 --- a/src/generateCubicConfiguration.m +++ b/src/generateCubicConfiguration.m @@ -5,7 +5,7 @@ function [stewart] = generateCubicConfiguration(stewart, args) % % Inputs: % - stewart - A structure with the following fields -% - H [1x1] - Total height of the platform [m] +% - geometry.H [1x1] - Total height of the platform [m] % - args - Can have the following fields: % - Hc [1x1] - Height of the "useful" part of the cube [m] % - FOc [1x1] - Height of the center of the cube with respect to {F} [m] @@ -14,17 +14,20 @@ function [stewart] = generateCubicConfiguration(stewart, args) % % Outputs: % - stewart - updated Stewart structure with the added fields: -% - Fa [3x6] - Its i'th column is the position vector of joint ai with respect to {F} -% - Mb [3x6] - Its i'th column is the position vector of joint bi with respect to {M} +% - 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.Hc (1,1) double {mustBeNumeric, mustBePositive} = 60e-3 args.FOc (1,1) double {mustBeNumeric} = 50e-3 - args.FHa (1,1) double {mustBeNumeric, mustBePositive} = 15e-3 - args.MHb (1,1) double {mustBeNumeric, mustBePositive} = 15e-3 + args.FHa (1,1) double {mustBeNumeric, mustBeNonnegative} = 15e-3 + args.MHb (1,1) double {mustBeNumeric, mustBeNonnegative} = 15e-3 end +assert(isfield(stewart.geometry, 'H'), 'stewart.geometry should have attribute H') +H = stewart.geometry.H; + sx = [ 2; -1; -1]; sy = [ 0; 1; -1]; sz = [ 1; 1; 1]; @@ -40,5 +43,8 @@ CCm = [Cc(:,2), Cc(:,2), Cc(:,4), Cc(:,4), Cc(:,6), Cc(:,6)]; % CCm(:,i) corresp CSi = (CCm - CCf)./vecnorm(CCm - CCf); -stewart.Fa = CCf + [0; 0; args.FOc] + ((args.FHa-(args.FOc-args.Hc/2))./CSi(3,:)).*CSi; -stewart.Mb = CCf + [0; 0; args.FOc-stewart.H] + ((stewart.H-args.MHb-(args.FOc-args.Hc/2))./CSi(3,:)).*CSi; +Fa = CCf + [0; 0; args.FOc] + ((args.FHa-(args.FOc-args.Hc/2))./CSi(3,:)).*CSi; +Mb = CCf + [0; 0; args.FOc-H] + ((H-args.MHb-(args.FOc-args.Hc/2))./CSi(3,:)).*CSi; + +stewart.platform_F.Fa = Fa; +stewart.platform_M.Mb = Mb; diff --git a/src/generateGeneralConfiguration.m b/src/generateGeneralConfiguration.m index 4fd7064..fbb570d 100644 --- a/src/generateGeneralConfiguration.m +++ b/src/generateGeneralConfiguration.m @@ -14,23 +14,26 @@ function [stewart] = generateGeneralConfiguration(stewart, args) % % Outputs: % - stewart - updated Stewart structure with the added fields: -% - Fa [3x6] - Its i'th column is the position vector of joint ai with respect to {F} -% - Mb [3x6] - Its i'th column is the position vector of joint bi with respect to {M} +% - 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} = 90e-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} = 70e-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 -stewart.Fa = zeros(3,6); -stewart.Mb = zeros(3,6); +Fa = zeros(3,6); +Mb = zeros(3,6); for i = 1:6 - stewart.Fa(:,i) = [args.FR*cos(args.FTh(i)); args.FR*sin(args.FTh(i)); args.FH]; - stewart.Mb(:,i) = [args.MR*cos(args.MTh(i)); args.MR*sin(args.MTh(i)); -args.MH]; + 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/src/initializeAmplifiedStrutDynamics.m b/src/initializeAmplifiedStrutDynamics.m new file mode 100644 index 0000000..a22bdb0 --- /dev/null +++ b/src/initializeAmplifiedStrutDynamics.m @@ -0,0 +1,43 @@ +function [stewart] = initializeAmplifiedStrutDynamics(stewart, args) +% initializeAmplifiedStrutDynamics - Add Stiffness and Damping properties of each strut +% +% Syntax: [stewart] = initializeAmplifiedStrutDynamics(args) +% +% Inputs: +% - args - Structure with the following fields: +% - Ka [6x1] - Vertical stiffness contribution of the piezoelectric stack [N/m] +% - Ca [6x1] - Vertical damping contribution of the piezoelectric stack [N/(m/s)] +% - Kr [6x1] - Vertical (residual) stiffness when the piezoelectric stack is removed [N/m] +% - Cr [6x1] - Vertical (residual) damping when the piezoelectric stack is removed [N/(m/s)] +% +% Outputs: +% - stewart - updated Stewart structure with the added fields: +% - actuators.type = 2 +% - actuators.K [6x1] - Total Stiffness of each strut [N/m] +% - actuators.C [6x1] - Total Damping of each strut [N/(m/s)] +% - actuators.Ka [6x1] - Vertical stiffness contribution of the piezoelectric stack [N/m] +% - actuators.Ca [6x1] - Vertical damping contribution of the piezoelectric stack [N/(m/s)] +% - actuators.Kr [6x1] - Vertical stiffness when the piezoelectric stack is removed [N/m] +% - actuators.Cr [6x1] - Vertical damping when the piezoelectric stack is removed [N/(m/s)] + +arguments + stewart + args.Kr (6,1) double {mustBeNumeric, mustBeNonnegative} = 5e6*ones(6,1) + args.Cr (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e1*ones(6,1) + args.Ka (6,1) double {mustBeNumeric, mustBeNonnegative} = 15e6*ones(6,1) + args.Ca (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e1*ones(6,1) +end + +K = args.Ka + args.Kr; +C = args.Ca + args.Cr; + +stewart.actuators.type = 2; + +stewart.actuators.Ka = args.Ka; +stewart.actuators.Ca = args.Ca; + +stewart.actuators.Kr = args.Kr; +stewart.actuators.Cr = args.Cr; + +stewart.actuators.K = K; +stewart.actuators.C = K; diff --git a/src/initializeCylindricalPlatforms.m b/src/initializeCylindricalPlatforms.m index 6f93b1f..0b86fc1 100644 --- a/src/initializeCylindricalPlatforms.m +++ b/src/initializeCylindricalPlatforms.m @@ -14,15 +14,17 @@ function [stewart] = initializeCylindricalPlatforms(stewart, args) % % Outputs: % - stewart - updated Stewart structure with the added fields: -% - platforms [struct] - structure with the following fields: -% - Fpm [1x1] - Fixed Platform Mass [kg] -% - Msi [3x3] - Mobile Platform Inertia matrix [kg*m^2] -% - Fph [1x1] - Fixed Platform Height [m] -% - Fpr [1x1] - Fixed Platform Radius [m] -% - Mpm [1x1] - Mobile Platform Mass [kg] -% - Fsi [3x3] - Fixed Platform Inertia matrix [kg*m^2] -% - Mph [1x1] - Mobile Platform Height [m] -% - Mpr [1x1] - Mobile Platform Radius [m] +% - 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 @@ -34,20 +36,24 @@ arguments args.Mpr (1,1) double {mustBeNumeric, mustBePositive} = 100e-3 end -platforms = struct(); +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]); -platforms.Fpm = args.Fpm; -platforms.Fph = args.Fph; -platforms.Fpr = args.Fpr; -platforms.Fpi = diag([1/12 * platforms.Fpm * (3*platforms.Fpr^2 + platforms.Fph^2), ... - 1/12 * platforms.Fpm * (3*platforms.Fpr^2 + platforms.Fph^2), ... - 1/2 * platforms.Fpm * platforms.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]); -platforms.Mpm = args.Mpm; -platforms.Mph = args.Mph; -platforms.Mpr = args.Mpr; -platforms.Mpi = diag([1/12 * platforms.Mpm * (3*platforms.Mpr^2 + platforms.Mph^2), ... - 1/12 * platforms.Mpm * (3*platforms.Mpr^2 + platforms.Mph^2), ... - 1/2 * platforms.Mpm * platforms.Mpr^2]); +stewart.platform_F.type = 1; -stewart.platforms = platforms; +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/src/initializeCylindricalStruts.m b/src/initializeCylindricalStruts.m index a83d0c5..2bb7257 100644 --- a/src/initializeCylindricalStruts.m +++ b/src/initializeCylindricalStruts.m @@ -14,15 +14,16 @@ function [stewart] = initializeCylindricalStruts(stewart, args) % % Outputs: % - stewart - updated Stewart structure with the added fields: -% - struts [struct] - structure with the following fields: -% - Fsm [6x1] - Mass of the Fixed part of the struts [kg] -% - Fsi [3x3x6] - Moment of Inertia for the Fixed part of the struts [kg*m^2] -% - Msm [6x1] - Mass of the Mobile part of the struts [kg] -% - Msi [3x3x6] - Moment of Inertia for the Mobile part of the struts [kg*m^2] -% - Fsh [6x1] - Height of cylinder for the Fixed part of the struts [m] -% - Fsr [6x1] - Radius of cylinder for the Fixed part of the struts [m] -% - Msh [6x1] - Height of cylinder for the Mobile part of the struts [m] -% - Msr [6x1] - Radius of cylinder for the Mobile part of the struts [m] +% - 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 @@ -34,25 +35,37 @@ arguments args.Msr (1,1) double {mustBeNumeric, mustBePositive} = 5e-3 end -struts = struct(); +Fsm = ones(6,1).*args.Fsm; +Fsh = ones(6,1).*args.Fsh; +Fsr = ones(6,1).*args.Fsr; -struts.Fsm = ones(6,1).*args.Fsm; -struts.Msm = ones(6,1).*args.Msm; +Msm = ones(6,1).*args.Msm; +Msh = ones(6,1).*args.Msh; +Msr = ones(6,1).*args.Msr; -struts.Fsh = ones(6,1).*args.Fsh; -struts.Fsr = ones(6,1).*args.Fsr; -struts.Msh = ones(6,1).*args.Msh; -struts.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 -struts.Fsi = zeros(3, 3, 6); -struts.Msi = zeros(3, 3, 6); for i = 1:6 - struts.Fsi(:,:,i) = diag([1/12 * struts.Fsm(i) * (3*struts.Fsr(i)^2 + struts.Fsh(i)^2), ... - 1/12 * struts.Fsm(i) * (3*struts.Fsr(i)^2 + struts.Fsh(i)^2), ... - 1/2 * struts.Fsm(i) * struts.Fsr(i)^2]); - struts.Msi(:,:,i) = diag([1/12 * struts.Msm(i) * (3*struts.Msr(i)^2 + struts.Msh(i)^2), ... - 1/12 * struts.Msm(i) * (3*struts.Msr(i)^2 + struts.Msh(i)^2), ... - 1/2 * struts.Msm(i) * struts.Msr(i)^2]); + 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 = struts; +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/src/initializeFramesPositions.m b/src/initializeFramesPositions.m index efb99a5..f68b97d 100644 --- a/src/initializeFramesPositions.m +++ b/src/initializeFramesPositions.m @@ -1,7 +1,7 @@ -function [stewart] = initializeFramesPositions(args) +function [stewart] = initializeFramesPositions(stewart, args) % initializeFramesPositions - Initialize the positions of frames {A}, {B}, {F} and {M} % -% Syntax: [stewart] = initializeFramesPositions(args) +% Syntax: [stewart] = initializeFramesPositions(stewart, args) % % Inputs: % - args - Can have the following fields: @@ -10,22 +10,26 @@ function [stewart] = initializeFramesPositions(args) % % Outputs: % - stewart - A structure with the following fields: -% - H [1x1] - Total Height of the Stewart Platform [m] -% - FO_M [3x1] - Position of {M} with respect to {F} [m] -% - MO_B [3x1] - Position of {B} with respect to {M} [m] -% - FO_A [3x1] - Position of {A} with respect to {F} [m] +% - 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 -stewart = struct(); +H = args.H; % Total Height of the Stewart Platform [m] -stewart.H = args.H; % Total Height of the Stewart Platform [m] +FO_M = [0; 0; H]; % Position of {M} with respect to {F} [m] -stewart.FO_M = [0; 0; stewart.H]; % Position of {M} with respect to {F} [m] +MO_B = [0; 0; args.MO_B]; % Position of {B} with respect to {M} [m] -stewart.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.FO_A = stewart.MO_B + stewart.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/src/initializeInertialSensor.m b/src/initializeInertialSensor.m new file mode 100644 index 0000000..a9509e4 --- /dev/null +++ b/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/src/initializeJointDynamics.m b/src/initializeJointDynamics.m new file mode 100644 index 0000000..e82d417 --- /dev/null +++ b/src/initializeJointDynamics.m @@ -0,0 +1,92 @@ +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' + args.type_M char {mustBeMember(args.type_M,{'universal', 'spherical', 'universal_p', 'spherical_p'})} = 'spherical' + args.Kf_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 15*ones(6,1) + args.Cf_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-4*ones(6,1) + args.Kt_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 20*ones(6,1) + args.Ct_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-3*ones(6,1) + args.Kf_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 15*ones(6,1) + args.Cf_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-4*ones(6,1) + args.Kt_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 20*ones(6,1) + args.Ct_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-3*ones(6,1) +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; +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; +end + +stewart.joints_M.Kx = zeros(6,1); +stewart.joints_M.Ky = zeros(6,1); +stewart.joints_M.Kz = zeros(6,1); + +stewart.joints_F.Kx = zeros(6,1); +stewart.joints_F.Ky = zeros(6,1); +stewart.joints_F.Kz = zeros(6,1); + +stewart.joints_M.Cx = zeros(6,1); +stewart.joints_M.Cy = zeros(6,1); +stewart.joints_M.Cz = zeros(6,1); + +stewart.joints_F.Cx = zeros(6,1); +stewart.joints_F.Cy = zeros(6,1); +stewart.joints_F.Cz = zeros(6,1); + +stewart.joints_M.Kf = args.Kf_M; +stewart.joints_M.Kt = args.Kf_M; + +stewart.joints_F.Kf = args.Kf_F; +stewart.joints_F.Kt = args.Kf_F; + +stewart.joints_M.Cf = args.Cf_M; +stewart.joints_M.Ct = args.Cf_M; + +stewart.joints_F.Cf = args.Cf_F; +stewart.joints_F.Ct = args.Cf_F; diff --git a/src/initializeMicroHexapod.m b/src/initializeMicroHexapod.m index c7f31d5..643d81e 100644 --- a/src/initializeMicroHexapod.m +++ b/src/initializeMicroHexapod.m @@ -36,37 +36,75 @@ arguments args.Foffset logical {mustBeNumericOrLogical} = false end -micro_hexapod = initializeFramesPositions('H', args.H, 'MO_B', args.MO_B); -micro_hexapod = generateGeneralConfiguration(micro_hexapod, 'FH', args.FH, 'FR', args.FR, 'FTh', args.FTh, 'MH', args.MH, 'MR', args.MR, 'MTh', args.MTh); -micro_hexapod = computeJointsPose(micro_hexapod); -micro_hexapod = initializeStrutDynamics(micro_hexapod, 'Ki', args.Ki, 'Ci', args.Ci); -micro_hexapod = initializeCylindricalPlatforms(micro_hexapod, 'Fpm', args.Fpm, 'Fph', args.Fph, 'Fpr', args.Fpr, 'Mpm', args.Mpm, 'Mph', args.Mph, 'Mpr', args.Mpr); -micro_hexapod = initializeCylindricalStruts(micro_hexapod, 'Fsm', args.Fsm, 'Fsh', args.Fsh, 'Fsr', args.Fsr, 'Msm', args.Msm, 'Msh', args.Msh, 'Msr', args.Msr); -micro_hexapod = computeJacobian(micro_hexapod); -[Li, dLi] = inverseKinematics(micro_hexapod, 'AP', args.AP, 'ARB', args.ARB); -micro_hexapod.Li = Li; -micro_hexapod.dLi = dLi; +stewart = initializeStewartPlatform(); + +stewart = initializeFramesPositions(stewart, ... + 'H', args.H, ... + 'MO_B', args.MO_B); + +stewart = generateGeneralConfiguration(stewart, ... + 'FH', args.FH, ... + 'FR', args.FR, ... + 'FTh', args.FTh, ... + 'MH', args.MH, ... + 'MR', args.MR, ... + 'MTh', args.MTh); + +stewart = computeJointsPose(stewart); + +stewart = initializeStrutDynamics(stewart, ... + 'K', args.Ki, ... + 'C', args.Ci); + +stewart = initializeJointDynamics(stewart, ... + 'type_F', 'universal_p', ... + 'type_M', 'spherical_p'); + +stewart = initializeCylindricalPlatforms(stewart, ... + 'Fpm', args.Fpm, ... + 'Fph', args.Fph, ... + 'Fpr', args.Fpr, ... + 'Mpm', args.Mpm, ... + 'Mph', args.Mph, ... + 'Mpr', args.Mpr); + +stewart = initializeCylindricalStruts(stewart, ... + 'Fsm', args.Fsm, ... + 'Fsh', args.Fsh, ... + 'Fsr', args.Fsr, ... + 'Msm', args.Msm, ... + 'Msh', args.Msh, ... + 'Msr', args.Msr); + +stewart = computeJacobian(stewart); + +stewart = initializeStewartPose(stewart, ... + 'AP', args.AP, ... + 'ARB', args.ARB); + +stewart = initializeInertialSensor(stewart, 'type', 'none'); if args.Foffset && ~strcmp(args.type, 'none') && ~strcmp(args.type, 'rigid') && ~strcmp(args.type, 'init') load('mat/Foffset.mat', 'Fhm'); - micro_hexapod.dLeq = -Fhm'./args.Ki; + stewart.actuators.dLeq = -Fhm'./args.Ki; else - micro_hexapod.dLeq = zeros(6,1); + stewart.actuators.dLeq = zeros(6,1); end switch args.type case 'none' - micro_hexapod.type = 0; + stewart.type = 0; case 'rigid' - micro_hexapod.type = 1; + stewart.type = 1; case 'flexible' - micro_hexapod.type = 2; + stewart.type = 2; case 'modal-analysis' - micro_hexapod.type = 3; + stewart.type = 3; case 'init' - micro_hexapod.type = 4; + stewart.type = 4; case 'compliance' - micro_hexapod.type = 5; + stewart.type = 5; end +micro_hexapod = stewart; save('./mat/stages.mat', 'micro_hexapod', '-append'); diff --git a/src/initializeNanoHexapod.m b/src/initializeNanoHexapod.m index 7ca7164..b00b4fe 100644 --- a/src/initializeNanoHexapod.m +++ b/src/initializeNanoHexapod.m @@ -16,6 +16,17 @@ arguments args.actuator char {mustBeMember(args.actuator,{'piezo', 'lorentz'})} = 'piezo' args.k (1,1) double {mustBeNumeric} = -1 args.c (1,1) double {mustBeNumeric} = -1 + % initializeJointDynamics + args.type_F char {mustBeMember(args.type_F,{'universal', 'spherical', 'universal_p', 'spherical_p'})} = 'universal' + args.type_M char {mustBeMember(args.type_M,{'universal', 'spherical', 'universal_p', 'spherical_p'})} = 'spherical' + args.Kf_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 15*ones(6,1) + args.Cf_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-4*ones(6,1) + args.Kt_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 20*ones(6,1) + args.Ct_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-3*ones(6,1) + args.Kf_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 15*ones(6,1) + args.Cf_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-4*ones(6,1) + args.Kt_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 20*ones(6,1) + args.Ct_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-3*ones(6,1) % initializeCylindricalPlatforms args.Fpm (1,1) double {mustBeNumeric, mustBePositive} = 1 args.Fph (1,1) double {mustBeNumeric, mustBePositive} = 10e-3 @@ -39,45 +50,65 @@ arguments args.Foffset logical {mustBeNumericOrLogical} = false end -nano_hexapod = initializeFramesPositions('H', args.H, 'MO_B', args.MO_B); -nano_hexapod = generateGeneralConfiguration(nano_hexapod, 'FH', args.FH, 'FR', args.FR, 'FTh', args.FTh, 'MH', args.MH, 'MR', args.MR, 'MTh', args.MTh); -nano_hexapod = computeJointsPose(nano_hexapod); +stewart = initializeStewartPlatform(); + +stewart = initializeFramesPositions(stewart, 'H', args.H, 'MO_B', args.MO_B); + +stewart = generateGeneralConfiguration(stewart, 'FH', args.FH, 'FR', args.FR, 'FTh', args.FTh, 'MH', args.MH, 'MR', args.MR, 'MTh', args.MTh); + +stewart = computeJointsPose(stewart); if args.k > 0 && args.c > 0 - nano_hexapod = initializeStrutDynamics(nano_hexapod, 'Ki', args.k*ones(6,1), 'Ci', args.c*ones(6,1)); + stewart = initializeStrutDynamics(stewart, 'K', args.k*ones(6,1), 'C', args.c*ones(6,1)); elseif args.k > 0 - nano_hexapod = initializeStrutDynamics(nano_hexapod, 'Ki', args.k*ones(6,1), 'Ci', 1.5*sqrt(args.k)*ones(6,1)); + stewart = initializeStrutDynamics(stewart, 'K', args.k*ones(6,1), 'C', 1.5*sqrt(args.k)*ones(6,1)); elseif strcmp(args.actuator, 'piezo') - nano_hexapod = initializeStrutDynamics(nano_hexapod, 'Ki', 1e7*ones(6,1), 'Ci', 1e2*ones(6,1)); + stewart = initializeStrutDynamics(stewart, 'K', 1e7*ones(6,1), 'C', 1e2*ones(6,1)); elseif strcmp(args.actuator, 'lorentz') - nano_hexapod = initializeStrutDynamics(nano_hexapod, 'Ki', 1e4*ones(6,1), 'Ci', 1e2*ones(6,1)); + stewart = initializeStrutDynamics(stewart, 'K', 1e4*ones(6,1), 'C', 1e2*ones(6,1)); else error('args.actuator should be piezo or lorentz'); end -nano_hexapod = initializeCylindricalPlatforms(nano_hexapod, 'Fpm', args.Fpm, 'Fph', args.Fph, 'Fpr', args.Fpr, 'Mpm', args.Mpm, 'Mph', args.Mph, 'Mpr', args.Mpr); -nano_hexapod = initializeCylindricalStruts(nano_hexapod, 'Fsm', args.Fsm, 'Fsh', args.Fsh, 'Fsr', args.Fsr, 'Msm', args.Msm, 'Msh', args.Msh, 'Msr', args.Msr); -nano_hexapod = computeJacobian(nano_hexapod); -[Li, dLi] = inverseKinematics(nano_hexapod, 'AP', args.AP, 'ARB', args.ARB); -nano_hexapod.Li = Li; -nano_hexapod.dLi = dLi; +stewart = initializeJointDynamics(stewart, ... + 'type_F', args.type_F, ... + 'type_M', args.type_M, ... + 'Kf_M' , args.Kf_M, ... + 'Cf_M' , args.Cf_M, ... + 'Kt_M' , args.Kt_M, ... + 'Ct_M' , args.Ct_M, ... + 'Kf_F' , args.Kf_F, ... + 'Cf_F' , args.Cf_F, ... + 'Kt_F' , args.Kt_F, ... + 'Ct_F' , args.Ct_F); + +stewart = initializeCylindricalPlatforms(stewart, 'Fpm', args.Fpm, 'Fph', args.Fph, 'Fpr', args.Fpr, 'Mpm', args.Mpm, 'Mph', args.Mph, 'Mpr', args.Mpr); + +stewart = initializeCylindricalStruts(stewart, 'Fsm', args.Fsm, 'Fsh', args.Fsh, 'Fsr', args.Fsr, 'Msm', args.Msm, 'Msh', args.Msh, 'Msr', args.Msr); + +stewart = computeJacobian(stewart); + +stewart = initializeStewartPose(stewart, 'AP', args.AP, 'ARB', args.ARB); + +stewart = initializeInertialSensor(stewart, 'type', 'accelerometer'); if args.Foffset && ~strcmp(args.type, 'none') && ~strcmp(args.type, 'rigid') && ~strcmp(args.type, 'init') load('mat/Foffset.mat', 'Fnm'); - nano_hexapod.dLeq = -Fnm'./nano_hexapod.Ki; + stewart.actuators.dLeq = -Fnm'./stewart.Ki; else - nano_hexapod.dLeq = args.dLeq; + stewart.actuators.dLeq = args.dLeq; end switch args.type case 'none' - nano_hexapod.type = 0; + stewart.type = 0; case 'rigid' - nano_hexapod.type = 1; + stewart.type = 1; case 'flexible' - nano_hexapod.type = 2; + stewart.type = 2; case 'init' - nano_hexapod.type = 4; + stewart.type = 4; end +nano_hexapod = stewart; save('./mat/stages.mat', 'nano_hexapod', '-append'); diff --git a/src/initializeStewartPlatform.m b/src/initializeStewartPlatform.m new file mode 100644 index 0000000..0545b4d --- /dev/null +++ b/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/src/initializeStewartPose.m b/src/initializeStewartPose.m new file mode 100644 index 0000000..325b501 --- /dev/null +++ b/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/src/initializeStrutDynamics.m b/src/initializeStrutDynamics.m index e4ba57f..23f4947 100644 --- a/src/initializeStrutDynamics.m +++ b/src/initializeStrutDynamics.m @@ -5,19 +5,22 @@ function [stewart] = initializeStrutDynamics(stewart, args) % % Inputs: % - args - Structure with the following fields: -% - Ki [6x1] - Stiffness of each strut [N/m] -% - Ci [6x1] - Damping of each strut [N/(m/s)] +% - 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: -% - Ki [6x1] - Stiffness of each strut [N/m] -% - Ci [6x1] - Damping of each strut [N/(m/s)] +% - 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.Ki (6,1) double {mustBeNumeric, mustBePositive} = 1e6*ones(6,1) - args.Ci (6,1) double {mustBeNumeric, mustBePositive} = 1e3*ones(6,1) + args.K (6,1) double {mustBeNumeric, mustBeNonnegative} = 20e6*ones(6,1) + args.C (6,1) double {mustBeNumeric, mustBeNonnegative} = 2e1*ones(6,1) end -stewart.Ki = args.Ki; -stewart.Ci = args.Ci; +stewart.actuators.type = 1; + +stewart.actuators.K = args.K; +stewart.actuators.C = args.C; diff --git a/src/inverseKinematics.m b/src/inverseKinematics.m index a214e1f..c1c0618 100644 --- a/src/inverseKinematics.m +++ b/src/inverseKinematics.m @@ -5,8 +5,9 @@ function [Li, dLi] = inverseKinematics(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} +% - 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} @@ -21,6 +22,15 @@ arguments args.ARB (3,3) double {mustBeNumeric} = eye(3) end -Li = sqrt(args.AP'*args.AP + diag(stewart.Bb'*stewart.Bb) + diag(stewart.Aa'*stewart.Aa) - (2*args.AP'*stewart.Aa)' + (2*args.AP'*(args.ARB*stewart.Bb))' - diag(2*(args.ARB*stewart.Bb)'*stewart.Aa)); +assert(isfield(stewart.geometry, 'Aa'), 'stewart.geometry should have attribute Aa') +Aa = stewart.geometry.Aa; -dLi = Li-stewart.l; +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;