From ed0c18829b83dfe9c34a5c469894cc47de60c1bc Mon Sep 17 00:00:00 2001
From: Thomas Dehaeze
-
-
The Matlab script corresponding to this section is accessible here.
@@ -106,44 +106,44 @@ To run the script, open the Simulink Project, and typerun active_damping_
1.1 Identification of the Dynamics
- stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart);
- stewart = initializeStrutDynamics(stewart);
- stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p');
- stewart = initializeCylindricalPlatforms(stewart);
- stewart = initializeCylindricalStruts(stewart);
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeInertialSensor(stewart, 'type', 'accelerometer', 'freq', 5e3);
+stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart);
+stewart = initializeStrutDynamics(stewart);
+stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p');
+stewart = initializeCylindricalPlatforms(stewart);
+stewart = initializeCylindricalStruts(stewart);
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeInertialSensor(stewart, 'type', 'accelerometer', 'freq', 5e3);
- ground = initializeGround('type', 'rigid', 'rot_point', stewart.platform_F.FO_A);
- payload = initializePayload('type', 'none');
- controller = initializeController('type', 'open-loop');
+ground = initializeGround('type', 'rigid', 'rot_point', stewart.platform_F.FO_A);
+payload = initializePayload('type', 'none');
+controller = initializeController('type', 'open-loop');
- %% Options for Linearized
- options = linearizeOptions;
- options.SampleTime = 0;
+%% Options for Linearized
+options = linearizeOptions;
+options.SampleTime = 0;
- %% Name of the Simulink File
- mdl = 'stewart_platform_model';
+%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
- io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'Vm'); io_i = io_i + 1; % Absolute velocity of each leg [m/s]
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
+io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'Vm'); io_i = io_i + 1; % Absolute velocity of each leg [m/s]
- %% Run the linearization
- G = linearize(mdl, io, options);
- G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
- G.OutputName = {'Vm1', 'Vm2', 'Vm3', 'Vm4', 'Vm5', 'Vm6'};
+%% Run the linearization
+G = linearize(mdl, io, options);
+G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
+G.OutputName = {'Vm1', 'Vm2', 'Vm3', 'Vm4', 'Vm5', 'Vm6'};
@@ -159,17 +159,17 @@ The transfer function from actuator forces to force sensors is shown in Figure <
We add some stiffness and damping in the flexible joints and we re-identify the dynamics.
stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical'); - Gf = linearize(mdl, io, options); - Gf.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; - Gf.OutputName = {'Vm1', 'Vm2', 'Vm3', 'Vm4', 'Vm5', 'Vm6'}; +stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical'); +Gf = linearize(mdl, io, options); +Gf.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; +Gf.OutputName = {'Vm1', 'Vm2', 'Vm3', 'Vm4', 'Vm5', 'Vm6'};
stewart = initializeAmplifiedStrutDynamics(stewart); - Ga = linearize(mdl, io, options); - Ga.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; - Ga.OutputName = {'Vm1', 'Vm2', 'Vm3', 'Vm4', 'Vm5', 'Vm6'}; +stewart = initializeAmplifiedStrutDynamics(stewart); +Ga = linearize(mdl, io, options); +Ga.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; +Ga.OutputName = {'Vm1', 'Vm2', 'Vm3', 'Vm4', 'Vm5', 'Vm6'};
The control is a performed in a decentralized manner. @@ -222,10 +222,10 @@ The root locus is shown in figure 3.
We do not have guaranteed stability with Inertial control. This is because of the flexibility inside the internal sensor.
@@ -242,7 +242,7 @@ We do not have guaranteed stability with Inertial control. This is because of th -The Matlab script corresponding to this section is accessible here.
@@ -254,31 +254,31 @@ To run the script, open the Simulink Project, and typerun active_damping_
We first initialize the Stewart platform without joint stiffness.
stewart = initializeStewartPlatform(); - stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3); - stewart = generateGeneralConfiguration(stewart); - stewart = computeJointsPose(stewart); - stewart = initializeStrutDynamics(stewart); - stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p'); - stewart = initializeCylindricalPlatforms(stewart); - stewart = initializeCylindricalStruts(stewart); - stewart = computeJacobian(stewart); - stewart = initializeStewartPose(stewart); - stewart = initializeInertialSensor(stewart, 'type', 'none'); +stewart = initializeStewartPlatform(); +stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3); +stewart = generateGeneralConfiguration(stewart); +stewart = computeJointsPose(stewart); +stewart = initializeStrutDynamics(stewart); +stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p'); +stewart = initializeCylindricalPlatforms(stewart); +stewart = initializeCylindricalStruts(stewart); +stewart = computeJacobian(stewart); +stewart = initializeStewartPose(stewart); +stewart = initializeInertialSensor(stewart, 'type', 'none');
ground = initializeGround('type', 'rigid', 'rot_point', stewart.platform_F.FO_A); - payload = initializePayload('type', 'none'); - controller = initializeController('type', 'open-loop'); +ground = initializeGround('type', 'rigid', 'rot_point', stewart.platform_F.FO_A); +payload = initializePayload('type', 'none'); +controller = initializeController('type', 'open-loop');
%% Name of the Simulink File - mdl = 'stewart_platform_model'; +%% Name of the Simulink File +mdl = 'stewart_platform_model'; - %% Input/Output definition - clear io; io_i = 1; - io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N] - io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'Taum'); io_i = io_i + 1; % Force Sensor Outputs [N] +%% Input/Output definition +clear io; io_i = 1; +io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N] +io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'Taum'); io_i = io_i + 1; % Force Sensor Outputs [N] - %% Run the linearization - G = linearize(mdl, io); - G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; - G.OutputName = {'Fm1', 'Fm2', 'Fm3', 'Fm4', 'Fm5', 'Fm6'}; +%% Run the linearization +G = linearize(mdl, io); +G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; +G.OutputName = {'Fm1', 'Fm2', 'Fm3', 'Fm4', 'Fm5', 'Fm6'};
We add some stiffness and damping in the flexible joints and we re-identify the dynamics.
stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical'); - Gf = linearize(mdl, io); - Gf.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; - Gf.OutputName = {'Fm1', 'Fm2', 'Fm3', 'Fm4', 'Fm5', 'Fm6'}; +stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical'); +Gf = linearize(mdl, io); +Gf.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; +Gf.OutputName = {'Fm1', 'Fm2', 'Fm3', 'Fm4', 'Fm5', 'Fm6'};
stewart = initializeAmplifiedStrutDynamics(stewart); - Ga = linearize(mdl, io); - Ga.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; - Ga.OutputName = {'Fm1', 'Fm2', 'Fm3', 'Fm4', 'Fm5', 'Fm6'}; +stewart = initializeAmplifiedStrutDynamics(stewart); +Ga = linearize(mdl, io); +Ga.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; +Ga.OutputName = {'Fm1', 'Fm2', 'Fm3', 'Fm4', 'Fm5', 'Fm6'};
The control is a performed in a decentralized manner. @@ -383,10 +383,10 @@ The root locus is shown in figure 6 and the obtained p
The joint stiffness has a huge impact on the attainable active damping performance when using force sensors. Thus, if Integral Force Feedback is to be used in a Stewart platform with flexible joints, the rotational stiffness of the joints should be minimized. @@ -404,7 +404,7 @@ Thus, if Integral Force Feedback is to be used in a Stewart platform with flexib
-The Matlab script corresponding to this section is accessible here.
@@ -416,31 +416,31 @@ To run the script, open the Simulink Project, and typerun active_damping_
We first initialize the Stewart platform without joint stiffness.
stewart = initializeStewartPlatform(); - stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3); - stewart = generateGeneralConfiguration(stewart); - stewart = computeJointsPose(stewart); - stewart = initializeStrutDynamics(stewart); - stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p'); - stewart = initializeCylindricalPlatforms(stewart); - stewart = initializeCylindricalStruts(stewart); - stewart = computeJacobian(stewart); - stewart = initializeStewartPose(stewart); - stewart = initializeInertialSensor(stewart, 'type', 'none'); +stewart = initializeStewartPlatform(); +stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3); +stewart = generateGeneralConfiguration(stewart); +stewart = computeJointsPose(stewart); +stewart = initializeStrutDynamics(stewart); +stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p'); +stewart = initializeCylindricalPlatforms(stewart); +stewart = initializeCylindricalStruts(stewart); +stewart = computeJacobian(stewart); +stewart = initializeStewartPose(stewart); +stewart = initializeInertialSensor(stewart, 'type', 'none');
ground = initializeGround('type', 'rigid', 'rot_point', stewart.platform_F.FO_A); - payload = initializePayload('type', 'none'); - controller = initializeController('type', 'open-loop'); +ground = initializeGround('type', 'rigid', 'rot_point', stewart.platform_F.FO_A); +payload = initializePayload('type', 'none'); +controller = initializeController('type', 'open-loop');
%% Options for Linearized - options = linearizeOptions; - options.SampleTime = 0; +%% Options for Linearized +options = linearizeOptions; +options.SampleTime = 0; - %% Name of the Simulink File - mdl = 'stewart_platform_model'; +%% Name of the Simulink File +mdl = 'stewart_platform_model'; - %% Input/Output definition - clear io; io_i = 1; - io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N] - io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'dLm'); io_i = io_i + 1; % Relative Displacement Outputs [m] +%% Input/Output definition +clear io; io_i = 1; +io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N] +io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'dLm'); io_i = io_i + 1; % Relative Displacement Outputs [m] - %% Run the linearization - G = linearize(mdl, io, options); - G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; - G.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6'}; +%% Run the linearization +G = linearize(mdl, io, options); +G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; +G.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6'};
We add some stiffness and damping in the flexible joints and we re-identify the dynamics.
stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical'); - Gf = linearize(mdl, io, options); - Gf.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; - Gf.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6'}; +stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical'); +Gf = linearize(mdl, io, options); +Gf.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; +Gf.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6'};
stewart = initializeAmplifiedStrutDynamics(stewart); - Ga = linearize(mdl, io, options); - Ga.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; - Ga.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6'}; +stewart = initializeAmplifiedStrutDynamics(stewart); +Ga = linearize(mdl, io, options); +Ga.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; +Ga.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6'};
The control is a performed in a decentralized manner. @@ -543,10 +543,10 @@ The root locus is shown in figure 10.
Joint stiffness does increase the resonance frequencies of the system but does not change the attainable damping when using relative motion sensors.
@@ -567,17 +567,17 @@ Joint stiffness does increase the resonance frequencies of the system but does n We first initialize the Stewart platform without joint stiffness.stewart = initializeStewartPlatform(); - stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3); - stewart = generateGeneralConfiguration(stewart); - stewart = computeJointsPose(stewart); - stewart = initializeStrutDynamics(stewart); - stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p'); - stewart = initializeCylindricalPlatforms(stewart); - stewart = initializeCylindricalStruts(stewart); - stewart = computeJacobian(stewart); - stewart = initializeStewartPose(stewart); - stewart = initializeInertialSensor(stewart, 'type', 'none'); +stewart = initializeStewartPlatform(); +stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3); +stewart = generateGeneralConfiguration(stewart); +stewart = computeJointsPose(stewart); +stewart = initializeStrutDynamics(stewart); +stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p'); +stewart = initializeCylindricalPlatforms(stewart); +stewart = initializeCylindricalStruts(stewart); +stewart = computeJacobian(stewart); +stewart = initializeStewartPose(stewart); +stewart = initializeInertialSensor(stewart, 'type', 'none');
ground = initializeGround('type', 'rigid', 'rot_point', stewart.platform_F.FO_A); - payload = initializePayload('type', 'none'); - controller = initializeController('type', 'open-loop'); +ground = initializeGround('type', 'rigid', 'rot_point', stewart.platform_F.FO_A); +payload = initializePayload('type', 'none'); +controller = initializeController('type', 'open-loop');
controller = initializeController('type', 'open-loop'); - [T_ol, T_norm_ol, freqs] = computeTransmissibility(); - [C_ol, C_norm_ol, freqs] = computeCompliance(); +controller = initializeController('type', 'open-loop'); +[T_ol, T_norm_ol, freqs] = computeTransmissibility(); +[C_ol, C_norm_ol, freqs] = computeCompliance();
controller = initializeController('type', 'iff'); - K_iff = (1e4/s)*eye(6); +controller = initializeController('type', 'iff'); +K_iff = (1e4/s)*eye(6); - [T_iff, T_norm_iff, ~] = computeTransmissibility(); - [C_iff, C_norm_iff, ~] = computeCompliance(); +[T_iff, T_norm_iff, ~] = computeTransmissibility(); +[C_iff, C_norm_iff, ~] = computeCompliance();
controller = initializeController('type', 'dvf'); - K_dvf = 1e4*s/(1+s/2/pi/5000)*eye(6); +controller = initializeController('type', 'dvf'); +K_dvf = 1e4*s/(1+s/2/pi/5000)*eye(6); - [T_dvf, T_norm_dvf, ~] = computeTransmissibility(); - [C_dvf, C_norm_dvf, ~] = computeCompliance(); +[T_dvf, T_norm_dvf, ~] = computeTransmissibility(); +[C_dvf, C_norm_dvf, ~] = computeCompliance();
Created: 2021-01-08 ven. 15:30
+Created: 2021-01-08 ven. 15:53
The control architecture is shown in Figure 1. @@ -168,64 +168,64 @@ Then, a diagonal (decentralized) controller \(\bm{K}_\mathcal{L}\) is used such
% Stewart Platform - stewart = initializeStewartPlatform(); - stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3); - stewart = generateGeneralConfiguration(stewart); - stewart = computeJointsPose(stewart); - stewart = initializeStrutDynamics(stewart); - stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p'); - stewart = initializeCylindricalPlatforms(stewart); - stewart = initializeCylindricalStruts(stewart); - stewart = computeJacobian(stewart); - stewart = initializeStewartPose(stewart); - stewart = initializeInertialSensor(stewart, 'type', 'accelerometer', 'freq', 5e3); - - % Ground and Payload - ground = initializeGround('type', 'rigid'); - payload = initializePayload('type', 'none'); - - % Controller - controller = initializeController('type', 'open-loop'); - - % Disturbances and References - disturbances = initializeDisturbances(); - references = initializeReferences(stewart); +% Stewart Platform +stewart = initializeStewartPlatform(); +stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3); +stewart = generateGeneralConfiguration(stewart); +stewart = computeJointsPose(stewart); +stewart = initializeStrutDynamics(stewart); +stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p'); +stewart = initializeCylindricalPlatforms(stewart); +stewart = initializeCylindricalStruts(stewart); +stewart = computeJacobian(stewart); +stewart = initializeStewartPose(stewart); +stewart = initializeInertialSensor(stewart, 'type', 'accelerometer', 'freq', 5e3); + +% Ground and Payload +ground = initializeGround('type', 'rigid'); +payload = initializePayload('type', 'none'); + +% Controller +controller = initializeController('type', 'open-loop'); + +% Disturbances and References +disturbances = initializeDisturbances(); +references = initializeReferences(stewart);
Let’s identify the transfer function from \(\bm{\tau}\) to \(\bm{\mathcal{L}}\).
%% Name of the Simulink File - mdl = 'stewart_platform_model'; +%% Name of the Simulink File +mdl = 'stewart_platform_model'; - %% Input/Output definition - clear io; io_i = 1; - io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N] - io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'dLm'); io_i = io_i + 1; % Relative Displacement Outputs [m] +%% Input/Output definition +clear io; io_i = 1; +io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N] +io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'dLm'); io_i = io_i + 1; % Relative Displacement Outputs [m] - %% Run the linearization - G = linearize(mdl, io); - G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; - G.OutputName = {'L1', 'L2', 'L3', 'L4', 'L5', 'L6'}; +%% Run the linearization +G = linearize(mdl, io); +G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; +G.OutputName = {'L1', 'L2', 'L3', 'L4', 'L5', 'L6'};
The diagonal and off-diagonal terms of the plant are shown in Figure 2. @@ -245,8 +245,8 @@ We see that the plant is decoupled at low frequency which indicate that decentra
The controller consists of: @@ -261,8 +261,8 @@ The obtained loop gains corresponding to the diagonal elements are shown in Figu
wc = 2*pi*30; - Kl = diag(1./diag(abs(freqresp(G, wc)))) * wc/s * 1/(1 + s/3/wc); +wc = 2*pi*30; +Kl = diag(1./diag(abs(freqresp(G, wc)))) * wc/s * 1/(1 + s/3/wc);
Let’s define some reference path to follow.
t = [0:1e-4:10]; - - r = zeros(6, length(t)); - - r(1, :) = 1e-3.*t.*sin(2*pi*t); - r(2, :) = 1e-3.*t.*cos(2*pi*t); - r(3, :) = 1e-3.*t; - - references = initializeReferences(stewart, 't', t, 'r', r); +t = [0:1e-4:10]; + +r = zeros(6, length(t)); + +r(1, :) = 1e-3.*t.*sin(2*pi*t); +r(2, :) = 1e-3.*t.*cos(2*pi*t); +r(3, :) = 1e-3.*t; + +references = initializeReferences(stewart, 't', t, 'r', r);
figure; - plot3(squeeze(references.r.Data(1,1,:)), squeeze(references.r.Data(2,1,:)), squeeze(references.r.Data(3,1,:))); - xlabel('X [m]'); - ylabel('Y [m]'); - zlabel('Z [m]'); +figure; +plot3(squeeze(references.r.Data(1,1,:)), squeeze(references.r.Data(2,1,:)), squeeze(references.r.Data(3,1,:))); +xlabel('X [m]'); +ylabel('Y [m]'); +zlabel('Z [m]');
controller = initializeController('type', 'ref-track-L'); +controller = initializeController('type', 'ref-track-L');
set_param('stewart_platform_model', 'StopTime', '10') - sim('stewart_platform_model'); - simout_D = simout; +set_param('stewart_platform_model', 'StopTime', '10') +sim('stewart_platform_model'); +simout_D = simout;
save('./mat/control_tracking.mat', 'simout_D', '-append'); +save('./mat/control_tracking.mat', 'simout_D', '-append');
figure; - hold on; - plot3(simout_D.x.Xr.Data(:, 1), simout_D.x.Xr.Data(:, 2), simout_D.x.Xr.Data(:, 3), 'k-'); - plot3(squeeze(references.r.Data(1,1,:)), squeeze(references.r.Data(2,1,:)), squeeze(references.r.Data(3,1,:)), '--'); - hold off; - xlabel('X [m]'); ylabel('Y [m]'); zlabel('Z [m]'); - view([1,1,1]) - zlim([0, inf]); +figure; +hold on; +plot3(simout_D.x.Xr.Data(:, 1), simout_D.x.Xr.Data(:, 2), simout_D.x.Xr.Data(:, 3), 'k-'); +plot3(squeeze(references.r.Data(1,1,:)), squeeze(references.r.Data(2,1,:)), squeeze(references.r.Data(3,1,:)), '--'); +hold off; +xlabel('X [m]'); ylabel('Y [m]'); zlabel('Z [m]'); +view([1,1,1]) +zlim([0, inf]);
Such control architecture is easy to implement and give good results. @@ -397,8 +397,8 @@ However, as \(\mathcal{X}\) is not directly measured, it is possible that import
The centralized controller takes the position error \(\bm{\epsilon}_\mathcal{X}\) as an inputs and generate actuator forces \(\bm{\tau}\) (see Figure 8). @@ -426,7 +426,7 @@ Instead of designing a full MIMO controller \(K\), we first try to make the plan We can think of two ways to make the plant more diagonal that are described in sections 2.4 and 2.5.
-
Note here that the subtraction shown in Figure 8 is not a real subtraction.
It is indeed a more complex computation explained in section 5.
@@ -436,57 +436,57 @@ It is indeed a more complex computation explained in section
-
Let’s identify the transfer function from \(\bm{\tau}\) to \(\bm{\mathcal{X}}\).
The pose error \(\bm{\epsilon}_\mathcal{X}\) is first converted in the frame of the leg by using the Jacobian matrix.
@@ -521,16 +521,16 @@ Note here that the transformation from the pose error \(\bm{\epsilon}_\mathcal{X
We now multiply the plant by the Jacobian matrix as shown in Figure 9 to obtain a more diagonal plant.
The controller consists of:
@@ -578,8 +578,8 @@ The obtained loop gains corresponding to the diagonal elements are shown in Figu
We specify the reference path to follow.
A diagonal controller \(\bm{K}_\mathcal{X}\) take the pose error \(\bm{\epsilon}_\mathcal{X}\) and generate cartesian forces \(\bm{\mathcal{F}}\) that are then converted to actuators forces using the Jacobian as shown in Figure e 12.
@@ -665,16 +665,16 @@ The final implemented controller is \(\bm{K} = \bm{J}^{-T} \cdot \bm{K}_\mathcal
We now multiply the plant by the Jacobian matrix as shown in Figure 12 to obtain a more diagonal plant.
The controller consists of:
@@ -797,8 +797,8 @@ The obtained loop gains corresponding to the diagonal elements are shown in Figu
We specify the reference path to follow.
The plant \(\bm{G}\) is pre-multiply by \(\bm{G}^{-1}(\omega = 0)\) such that the “shaped plant” \(\bm{G}_0 = \bm{G} \bm{G}^{-1}(\omega = 0)\) is diagonal at low frequency.
@@ -888,8 +888,8 @@ The control architecture is shown in Figure 15.
The plant is pre-multiplied by \(\bm{G}^{-1}(\omega = 0)\).
@@ -897,7 +897,7 @@ The diagonal and off-diagonal elements of the shaped plant are shown in Figure <
We have that:
@@ -977,8 +977,8 @@ This error is much lower when using the diagonal control in the frame of the leg
Both control architecture gives similar results even tough the control in the Leg’s frame gives slightly better results.
@@ -1061,8 +1061,8 @@ Thus, this method should be quite robust against parameter variation (e.g. the p
Let’s consider the control schematic shown in Figure 19.
@@ -1103,33 +1103,33 @@ This second loop is responsible for the reference tracking.
Let’s identify the transfer function from \(\bm{\tau}\) to \(\bm{L}\).
We apply a decentralized (diagonal) direct velocity feedback.
@@ -1194,7 +1194,7 @@ The obtain loop gain is shown in Figure 21.
We use the Jacobian matrix to apply forces in the cartesian frame.
The controller consists of:
@@ -1278,14 +1278,14 @@ The controller consists of:
Created: 2021-01-08 ven. 15:30 Created: 2021-01-08 ven. 15:53
We first initialize the Stewart platform.
We identify the transfer function from the actuator forces \(\bm{\tau}\) to the absolute displacement of the mobile platform \(\bm{\mathcal{X}}\) in three different cases:
@@ -201,81 +201,81 @@ We identify the transfer function from the actuator forces \(\bm{\tau}\) to the
We design a diagonal controller with equal bandwidth for the 6 terms.
@@ -344,12 +344,12 @@ The controller is a pure integrator with a small lead near the crossover.
We identify the transmissibility and compliance of the system.
We design a diagonal controller with equal bandwidth for the 6 terms.
@@ -434,12 +434,12 @@ The controller is a pure integrator with a small lead near the crossover.
We identify the transmissibility and compliance of the system.
We first initialize the Stewart platform.
We first initialize the Stewart platform.
We identify the transmissibility and compliance of the Stewart platform under open-loop and closed-loop control.
We first initialize the Stewart platform.
Created: 2021-01-08 ven. 15:29 Created: 2021-01-08 ven. 15:52
The Matlab script corresponding to this section is accessible here.
Here are the conclusion about the Stiffness matrix for the Cubic configuration:
The Matlab script corresponding to this section is accessible here.
We found that we can have a diagonal stiffness matrix using the cubic architecture when \(\{A\}\) and \(\{B\}\) are located above the top platform.
Depending on the cube’s size, we obtain 3 different configurations.
@@ -1102,7 +1102,7 @@ Depending on the cube’s size, we obtain 3 different configurations.
The Matlab script corresponding to this section is accessible here.
We observe that \(k_{\theta_x} = k_{\theta_y}\) and \(k_{\theta_z}\) increase linearly with the cube size.
In order to maximize the rotational stiffness of the Stewart platform, the size of the cube should be the highest possible.
The Matlab script corresponding to this section is accessible here.
The dynamics is well decoupled at all frequencies.
Figure 14: Obtained Dynamics from \(\bm{\mathcal{F}}\) to \(\bm{\mathcal{X}}\) (png, pdf)
The system is decoupled at low frequency (the Stiffness matrix being diagonal), but it is not decoupled at all frequencies.
Some conclusions can be drawn from the above analysis:
The Matlab script corresponding to this section is accessible here.
The Cubic architecture seems to not have any significant effect on the coupling between actuator and sensors of each strut and thus provides no advantages for decentralized control.
Created: 2021-01-08 ven. 15:30 Created: 2021-01-08 ven. 15:52
The transfer function from forces/torques applied by the actuators on the payload \(\bm{\mathcal{F}} = \bm{J}^T \bm{\tau}\) to the pose of the mobile platform \(\bm{\mathcal{X}}\) is the same as the transfer function from external forces/torques to \(\bm{\mathcal{X}}\) as long as the Stewart platform’s base is fixed.
The low frequency transfer function matrix from \(\mathcal{\bm{F}}\) to \(\mathcal{\bm{X}}\) corresponds to the compliance matrix of the Stewart platform.
Created: 2021-01-08 ven. 15:30 Created: 2021-01-08 ven. 15:52
And we identify the dynamics from force actuators to force sensors.
The results seems to indicate that the model is well represented with only few degrees of freedom.
This permit to have a relatively sane number of states for the model.
@@ -588,66 +588,66 @@ This permit to have a relatively sane number of states for the model.
And we identify the dynamics from force actuators to force sensors.
Qualitatively:
@@ -891,118 +891,118 @@ Quantitatively:
Created: 2021-01-08 ven. 15:29 Created: 2021-01-08 ven. 15:52 Created: 2021-01-08 ven. 15:29 Created: 2021-01-08 ven. 15:52
The Matlab script corresponding to this section is accessible here.
We first define some general Stewart architecture.
For small wanted displacements (up to \(\approx 1\%\) of the size of the Hexapod), the approximate inverse kinematic solution using the Jacobian matrix is quite correct.
The Matlab script corresponding to this section is accessible here.
Let’s first define the Stewart platform architecture that we want to study.
The Matlab script corresponding to this section is accessible here.
Let’s first define the Stewart platform architecture that we want to study.
Created: 2021-01-08 ven. 15:17 Created: 2021-01-08 ven. 15:52 Created: 2021-01-08 ven. 15:30 Created: 2021-01-08 ven. 15:53 Created: 2021-01-08 ven. 15:29 Created: 2021-01-08 ven. 15:52 Created: 2021-01-08 ven. 15:30 Created: 2021-01-08 ven. 15:52 Created: 2021-01-08 ven. 15:30 Created: 2021-01-08 ven. 15:53
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 9).
@@ -877,46 +877,46 @@ The radius of the circles can be chosen as well as the angles where the joints a
@@ -977,76 +977,76 @@ This Matlab function is accessible here
2.2 Initialize the Stewart platform
+2.2 Initialize the Stewart platform
% Stewart Platform
- stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart);
- stewart = initializeStrutDynamics(stewart);
- stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p');
- stewart = initializeCylindricalPlatforms(stewart);
- stewart = initializeCylindricalStruts(stewart);
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeInertialSensor(stewart, 'type', 'accelerometer', 'freq', 5e3);
-
- % Ground and Payload
- ground = initializeGround('type', 'rigid');
- payload = initializePayload('type', 'none');
-
- % Controller
- controller = initializeController('type', 'open-loop');
-
- % Disturbances and References
- disturbances = initializeDisturbances();
- references = initializeReferences(stewart);
+
% Stewart Platform
+stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart);
+stewart = initializeStrutDynamics(stewart);
+stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p');
+stewart = initializeCylindricalPlatforms(stewart);
+stewart = initializeCylindricalStruts(stewart);
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeInertialSensor(stewart, 'type', 'accelerometer', 'freq', 5e3);
+
+% Ground and Payload
+ground = initializeGround('type', 'rigid');
+payload = initializePayload('type', 'none');
+
+% Controller
+controller = initializeController('type', 'open-loop');
+
+% Disturbances and References
+disturbances = initializeDisturbances();
+references = initializeReferences(stewart);
2.3 Identification of the plant
+2.3 Identification of the plant
%% Name of the Simulink File
- mdl = 'stewart_platform_model';
+
%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
- io(io_i) = linio([mdl, '/Relative Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Relative Displacement Outputs [m]
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
+io(io_i) = linio([mdl, '/Relative Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Relative Displacement Outputs [m]
- %% Run the linearization
- G = linearize(mdl, io);
- G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
- G.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
+%% Run the linearization
+G = linearize(mdl, io);
+G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
+G.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
2.4.1 Control Architecture
+2.4.1 Control Architecture
2.4.2 Plant Analysis
+2.4.2 Plant Analysis
Gl = stewart.kinematics.J*G;
- Gl.OutputName = {'D1', 'D2', 'D3', 'D4', 'D5', 'D6'};
+
Gl = stewart.kinematics.J*G;
+Gl.OutputName = {'D1', 'D2', 'D3', 'D4', 'D5', 'D6'};
2.4.3 Controller Design
+2.4.3 Controller Design
wc = 2*pi*30;
- Kl = diag(1./diag(abs(freqresp(Gl, wc)))) * wc/s * 1/(1 + s/3/wc);
+
wc = 2*pi*30;
+Kl = diag(1./diag(abs(freqresp(Gl, wc)))) * wc/s * 1/(1 + s/3/wc);
K = Kl*stewart.kinematics.J;
+
K = Kl*stewart.kinematics.J;
2.4.4 Simulation
+2.4.4 Simulation
t = [0:1e-4:10];
-
- r = zeros(6, length(t));
-
- r(1, :) = 1e-3.*t.*sin(2*pi*t);
- r(2, :) = 1e-3.*t.*cos(2*pi*t);
- r(3, :) = 1e-3.*t;
-
- references = initializeReferences(stewart, 't', t, 'r', r);
+
t = [0:1e-4:10];
+
+r = zeros(6, length(t));
+
+r(1, :) = 1e-3.*t.*sin(2*pi*t);
+r(2, :) = 1e-3.*t.*cos(2*pi*t);
+r(3, :) = 1e-3.*t;
+
+references = initializeReferences(stewart, 't', t, 'r', r);
controller = initializeController('type', 'ref-track-X');
+
controller = initializeController('type', 'ref-track-X');
set_param('stewart_platform_model', 'StopTime', '10')
- sim('stewart_platform_model')
- simout_L = simout;
- save('./mat/control_tracking.mat', 'simout_L', '-append');
+
set_param('stewart_platform_model', 'StopTime', '10')
+sim('stewart_platform_model')
+simout_L = simout;
+save('./mat/control_tracking.mat', 'simout_L', '-append');
2.5.1 Control Architecture
+2.5.1 Control Architecture
2.5.2 Plant Analysis
+2.5.2 Plant Analysis
Gx = G*inv(stewart.kinematics.J');
- Gx.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
+
Gx = G*inv(stewart.kinematics.J');
+Gx.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
2.5.3 Controller Design
+2.5.3 Controller Design
wc = 2*pi*30;
- Kx = diag(1./diag(abs(freqresp(Gx, wc)))) * wc/s * 1/(1 + s/3/wc);
+
wc = 2*pi*30;
+Kx = diag(1./diag(abs(freqresp(Gx, wc)))) * wc/s * 1/(1 + s/3/wc);
K = inv(stewart.kinematics.J')*Kx;
+
K = inv(stewart.kinematics.J')*Kx;
2.5.4 Simulation
+2.5.4 Simulation
t = [0:1e-4:10];
-
- r = zeros(6, length(t));
-
- r(1, :) = 1e-3.*t.*sin(2*pi*t);
- r(2, :) = 1e-3.*t.*cos(2*pi*t);
- r(3, :) = 1e-3.*t;
-
- references = initializeReferences(stewart, 't', t, 'r', r);
+
t = [0:1e-4:10];
+
+r = zeros(6, length(t));
+
+r(1, :) = 1e-3.*t.*sin(2*pi*t);
+r(2, :) = 1e-3.*t.*cos(2*pi*t);
+r(3, :) = 1e-3.*t;
+
+references = initializeReferences(stewart, 't', t, 'r', r);
controller = initializeController('type', 'ref-track-X');
+
controller = initializeController('type', 'ref-track-X');
set_param('stewart_platform_model', 'StopTime', '10')
- sim('stewart_platform_model')
- simout_X = simout;
- save('./mat/control_tracking.mat', 'simout_X', '-append');
+
set_param('stewart_platform_model', 'StopTime', '10')
+sim('stewart_platform_model')
+simout_X = simout;
+save('./mat/control_tracking.mat', 'simout_X', '-append');
2.6.1 Control Architecture
+2.6.1 Control Architecture
2.6.2 Plant Analysis
+2.6.2 Plant Analysis
G0 = G*inv(freqresp(G, 0));
+
G0 = G*inv(freqresp(G, 0));
2.6.3 Controller Design
+2.6.3 Controller Design
2.8 Conclusion
+2.8 Conclusion
3.1 Control Schematic
+3.1 Control Schematic
3.2 Initialize the Stewart platform
+3.2 Initialize the Stewart platform
% Stewart Platform
- stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart);
- stewart = initializeStrutDynamics(stewart);
- stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p');
- stewart = initializeCylindricalPlatforms(stewart);
- stewart = initializeCylindricalStruts(stewart);
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeInertialSensor(stewart, 'type', 'accelerometer', 'freq', 5e3);
-
- % Ground and Payload
- ground = initializeGround('type', 'rigid');
- payload = initializePayload('type', 'none');
-
- % Controller
- controller = initializeController('type', 'open-loop');
-
- % Disturbances and References
- disturbances = initializeDisturbances();
- references = initializeReferences(stewart);
+
% Stewart Platform
+stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart);
+stewart = initializeStrutDynamics(stewart);
+stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p');
+stewart = initializeCylindricalPlatforms(stewart);
+stewart = initializeCylindricalStruts(stewart);
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeInertialSensor(stewart, 'type', 'accelerometer', 'freq', 5e3);
+
+% Ground and Payload
+ground = initializeGround('type', 'rigid');
+payload = initializePayload('type', 'none');
+
+% Controller
+controller = initializeController('type', 'open-loop');
+
+% Disturbances and References
+disturbances = initializeDisturbances();
+references = initializeReferences(stewart);
3.3 First Control Loop - \(\bm{K}_\mathcal{L}\)
3.3.1 Identification
+3.3.1 Identification
%% Name of the Simulink File
- mdl = 'stewart_platform_model';
+
%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
- io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'dLm'); io_i = io_i + 1; % Relative Displacement Outputs [m]
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
+io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'dLm'); io_i = io_i + 1; % Relative Displacement Outputs [m]
- %% Run the linearization
- Gl = linearize(mdl, io);
- Gl.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
- Gl.OutputName = {'L1', 'L2', 'L3', 'L4', 'L5', 'L6'};
+%% Run the linearization
+Gl = linearize(mdl, io);
+Gl.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
+Gl.OutputName = {'L1', 'L2', 'L3', 'L4', 'L5', 'L6'};
3.3.2 Obtained Plant
+3.3.2 Obtained Plant
3.3.3 Controller Design
+3.3.3 Controller Design
Kl = 1e4 * s / (1 + s/2/pi/1e4) * eye(6);
+
Kl = 1e4 * s / (1 + s/2/pi/1e4) * eye(6);
3.4 Second Control Loop - \(\bm{K}_\mathcal{X}\)
3.4.1 Identification
+3.4.1 Identification
Kx = tf(zeros(6));
+
Kx = tf(zeros(6));
- controller = initializeController('type', 'ref-track-hac-dvf');
+controller = initializeController('type', 'ref-track-hac-dvf');
%% Name of the Simulink File
- mdl = 'stewart_platform_model';
+
%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Controller'], 1, 'input'); io_i = io_i + 1; % Actuator Force Inputs [N]
- io(io_i) = linio([mdl, '/Relative Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Relative Displacement Outputs [m]
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Controller'], 1, 'input'); io_i = io_i + 1; % Actuator Force Inputs [N]
+io(io_i) = linio([mdl, '/Relative Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Relative Displacement Outputs [m]
- %% Run the linearization
- G = linearize(mdl, io);
- G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
- G.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
+%% Run the linearization
+G = linearize(mdl, io);
+G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
+G.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
3.4.2 Obtained Plant
+3.4.2 Obtained Plant
Gx = G*inv(stewart.kinematics.J');
- Gx.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
+
Gx = G*inv(stewart.kinematics.J');
+Gx.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
3.4.3 Controller Design
+3.4.3 Controller Design
wc = 2*pi*200; % Bandwidth Bandwidth [rad/s]
+
wc = 2*pi*200; % Bandwidth Bandwidth [rad/s]
- h = 3; % Lead parameter
+h = 3; % Lead parameter
- Kx = (1/h) * (1 + s/wc*h)/(1 + s/wc/h) * wc/s * ((s/wc*2 + 1)/(s/wc*2)) * (1/(1 + s/wc/3));
+Kx = (1/h) * (1 + s/wc*h)/(1 + s/wc/h) * wc/s * ((s/wc*2 + 1)/(s/wc*2)) * (1/(1 + s/wc/3));
- % Normalization of the gain of have a loop gain of 1 at frequency wc
- Kx = Kx.*diag(1./diag(abs(freqresp(Gx*Kx, wc))));
+% Normalization of the gain of have a loop gain of 1 at frequency wc
+Kx = Kx.*diag(1./diag(abs(freqresp(Gx*Kx, wc))));
Kx = inv(stewart.kinematics.J')*Kx;
+
Kx = inv(stewart.kinematics.J')*Kx;
t = [0:1e-4:10];
-
- r = zeros(6, length(t));
-
- r(1, :) = 1e-3.*t.*sin(2*pi*t);
- r(2, :) = 1e-3.*t.*cos(2*pi*t);
- r(3, :) = 1e-3.*t;
-
- references = initializeReferences(stewart, 't', t, 'r', r);
+
t = [0:1e-4:10];
+
+r = zeros(6, length(t));
+
+r(1, :) = 1e-3.*t.*sin(2*pi*t);
+r(2, :) = 1e-3.*t.*cos(2*pi*t);
+r(3, :) = 1e-3.*t;
+
+references = initializeReferences(stewart, 't', t, 'r', r);
set_param('stewart_platform_model', 'StopTime', '10')
- sim('stewart_platform_model')
- simout_H = simout;
- save('./mat/control_tracking.mat', 'simout_H', '-append');
+
set_param('stewart_platform_model', 'StopTime', '10')
+sim('stewart_platform_model')
+simout_H = simout;
+save('./mat/control_tracking.mat', 'simout_H', '-append');
3.6 Conclusion
+3.6 Conclusion
load('./mat/control_tracking.mat', 'simout_D', 'simout_L', 'simout_X', 'simout_H');
+
load('./mat/control_tracking.mat', 'simout_D', 'simout_L', 'simout_X', 'simout_H');
Dxr = 0;
- Dyr = 0;
- Dzr = 0.1;
- Rxr = pi;
- Ryr = 0;
- Rzr = 0;
+
Dxr = 0;
+Dyr = 0;
+Dzr = 0.1;
+Rxr = pi;
+Ryr = 0;
+Rzr = 0;
Dxm = 0;
- Dym = 0;
- Dzm = 0;
- Rxm = pi;
- Rym = 0;
- Rzm = 0;
+
Dxm = 0;
+Dym = 0;
+Dzm = 0;
+Rxm = pi;
+Rym = 0;
+Rzm = 0;
%% Measured Pose
- WTm = zeros(4,4);
+
%% Measured Pose
+WTm = zeros(4,4);
- WTm(1:3, 1:3) = [cos(Rzm) -sin(Rzm) 0;
- sin(Rzm) cos(Rzm) 0;
- 0 0 1] * ...
- [cos(Rym) 0 sin(Rym);
- 0 1 0;
- -sin(Rym) 0 cos(Rym)] * ...
- [1 0 0;
- 0 cos(Rxm) -sin(Rxm);
- 0 sin(Rxm) cos(Rxm)];
- WTm(1:4, 4) = [Dxm ; Dym ; Dzm; 1];
+WTm(1:3, 1:3) = [cos(Rzm) -sin(Rzm) 0;
+ sin(Rzm) cos(Rzm) 0;
+ 0 0 1] * ...
+ [cos(Rym) 0 sin(Rym);
+ 0 1 0;
+ -sin(Rym) 0 cos(Rym)] * ...
+ [1 0 0;
+ 0 cos(Rxm) -sin(Rxm);
+ 0 sin(Rxm) cos(Rxm)];
+WTm(1:4, 4) = [Dxm ; Dym ; Dzm; 1];
%% Reference Pose
- WTr = zeros(4,4);
+
%% Reference Pose
+WTr = zeros(4,4);
- WTr(1:3, 1:3) = [cos(Rzr) -sin(Rzr) 0;
- sin(Rzr) cos(Rzr) 0;
- 0 0 1] * ...
- [cos(Ryr) 0 sin(Ryr);
- 0 1 0;
- -sin(Ryr) 0 cos(Ryr)] * ...
- [1 0 0;
- 0 cos(Rxr) -sin(Rxr);
- 0 sin(Rxr) cos(Rxr)];
- WTr(1:4, 4) = [Dxr ; Dyr ; Dzr; 1];
+WTr(1:3, 1:3) = [cos(Rzr) -sin(Rzr) 0;
+ sin(Rzr) cos(Rzr) 0;
+ 0 0 1] * ...
+ [cos(Ryr) 0 sin(Ryr);
+ 0 1 0;
+ -sin(Ryr) 0 cos(Ryr)] * ...
+ [1 0 0;
+ 0 cos(Rxr) -sin(Rxr);
+ 0 sin(Rxr) cos(Rxr)];
+WTr(1:4, 4) = [Dxr ; Dyr ; Dzr; 1];
WTv = eye(4);
- WTv(1:3, 4) = WTm(1:3, 4);
+
WTv = eye(4);
+WTv(1:3, 4) = WTm(1:3, 4);
%% Wanted pose expressed in a frame corresponding to the actual measured pose
- MTr = [WTm(1:3,1:3)', -WTm(1:3,1:3)'*WTm(1:3,4) ; 0 0 0 1]*WTr;
+
%% Wanted pose expressed in a frame corresponding to the actual measured pose
+MTr = [WTm(1:3,1:3)', -WTm(1:3,1:3)'*WTm(1:3,4) ; 0 0 0 1]*WTr;
%% Wanted pose expressed in a frame coincident with the actual position but with no rotation
- VTr = [WTv(1:3,1:3)', -WTv(1:3,1:3)'*WTv(1:3,4) ; 0 0 0 1] * WTr;
+
%% Wanted pose expressed in a frame coincident with the actual position but with no rotation
+VTr = [WTv(1:3,1:3)', -WTv(1:3,1:3)'*WTv(1:3,4) ; 0 0 0 1] * WTr;
%% Extract Translations and Rotations from the Homogeneous Matrix
- T = MTr;
- Edx = T(1, 4);
- Edy = T(2, 4);
- Edz = T(3, 4);
+
%% Extract Translations and Rotations from the Homogeneous Matrix
+T = MTr;
+Edx = T(1, 4);
+Edy = T(2, 4);
+Edz = T(3, 4);
- % The angles obtained are u-v-w Euler angles (rotations in the moving frame)
- Ery = atan2( T(1, 3), sqrt(T(1, 1)^2 + T(1, 2)^2));
- Erx = atan2(-T(2, 3)/cos(Ery), T(3, 3)/cos(Ery));
- Erz = atan2(-T(1, 2)/cos(Ery), T(1, 1)/cos(Ery));
+% The angles obtained are u-v-w Euler angles (rotations in the moving frame)
+Ery = atan2( T(1, 3), sqrt(T(1, 1)^2 + T(1, 2)^2));
+Erx = atan2(-T(2, 3)/cos(Ery), T(3, 3)/cos(Ery));
+Erz = atan2(-T(1, 2)/cos(Ery), T(1, 1)/cos(Ery));
1.2 Initialization
+1.2 Initialization
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart);
- stewart = initializeStrutDynamics(stewart);
- stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical');
- stewart = initializeCylindricalPlatforms(stewart);
- stewart = initializeCylindricalStruts(stewart);
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeInertialSensor(stewart, 'type', 'none');
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart);
+stewart = initializeStrutDynamics(stewart);
+stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical');
+stewart = initializeCylindricalPlatforms(stewart);
+stewart = initializeCylindricalStruts(stewart);
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeInertialSensor(stewart, 'type', 'none');
ground = initializeGround('type', 'rigid', 'rot_point', stewart.platform_F.FO_A);
- payload = initializePayload('type', 'none');
+
ground = initializeGround('type', 'rigid', 'rot_point', stewart.platform_F.FO_A);
+payload = initializePayload('type', 'none');
1.3 Identification
+1.3 Identification
1.3.1 HAC - Without LAC
+1.3.1 HAC - Without LAC
controller = initializeController('type', 'open-loop');
+
controller = initializeController('type', 'open-loop');
%% Name of the Simulink File
- mdl = 'stewart_platform_model';
+
%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Controller'], 1, 'input'); io_i = io_i + 1; % Actuator Force Inputs [N]
- io(io_i) = linio([mdl, '/Absolute Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Absolute Sensor [m, rad]
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Controller'], 1, 'input'); io_i = io_i + 1; % Actuator Force Inputs [N]
+io(io_i) = linio([mdl, '/Absolute Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Absolute Sensor [m, rad]
- %% Run the linearization
- G_ol = linearize(mdl, io);
- G_ol.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
- G_ol.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
+%% Run the linearization
+G_ol = linearize(mdl, io);
+G_ol.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
+G_ol.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
1.3.2 HAC - IFF
+1.3.2 HAC - IFF
controller = initializeController('type', 'iff');
- K_iff = -(1e4/s)*eye(6);
+
controller = initializeController('type', 'iff');
+K_iff = -(1e4/s)*eye(6);
%% Name of the Simulink File
- mdl = 'stewart_platform_model';
+
%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Controller'], 1, 'input'); io_i = io_i + 1; % Actuator Force Inputs [N]
- io(io_i) = linio([mdl, '/Absolute Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Absolute Sensor [m, rad]
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Controller'], 1, 'input'); io_i = io_i + 1; % Actuator Force Inputs [N]
+io(io_i) = linio([mdl, '/Absolute Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Absolute Sensor [m, rad]
- %% Run the linearization
- G_iff = linearize(mdl, io);
- G_iff.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
- G_iff.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
+%% Run the linearization
+G_iff = linearize(mdl, io);
+G_iff.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
+G_iff.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
1.3.3 HAC - DVF
+1.3.3 HAC - DVF
controller = initializeController('type', 'dvf');
- K_dvf = -1e4*s/(1+s/2/pi/5000)*eye(6);
+
controller = initializeController('type', 'dvf');
+K_dvf = -1e4*s/(1+s/2/pi/5000)*eye(6);
%% Name of the Simulink File
- mdl = 'stewart_platform_model';
+
%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Controller'], 1, 'input'); io_i = io_i + 1; % Actuator Force Inputs [N]
- io(io_i) = linio([mdl, '/Absolute Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Absolute Sensor [m, rad]
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Controller'], 1, 'input'); io_i = io_i + 1; % Actuator Force Inputs [N]
+io(io_i) = linio([mdl, '/Absolute Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Absolute Sensor [m, rad]
- %% Run the linearization
- G_dvf = linearize(mdl, io);
- G_dvf.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
- G_dvf.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
+%% Run the linearization
+G_dvf = linearize(mdl, io);
+G_dvf.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
+G_dvf.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
Gc_ol = minreal(G_ol)/stewart.kinematics.J';
- Gc_ol.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
+
Gc_ol = minreal(G_ol)/stewart.kinematics.J';
+Gc_ol.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
- Gc_iff = minreal(G_iff)/stewart.kinematics.J';
- Gc_iff.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
+Gc_iff = minreal(G_iff)/stewart.kinematics.J';
+Gc_iff.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
- Gc_dvf = minreal(G_dvf)/stewart.kinematics.J';
- Gc_dvf.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
+Gc_dvf = minreal(G_dvf)/stewart.kinematics.J';
+Gc_dvf.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
1.6 HAC - DVF
+1.6 HAC - DVF
1.6.1 Plant
+1.6.1 Plant
1.6.2 Controller Design
+1.6.2 Controller Design
wc = 2*pi*300; % Wanted Bandwidth [rad/s]
+
wc = 2*pi*300; % Wanted Bandwidth [rad/s]
- h = 1.2;
- H_lead = 1/h*(1 + s/(wc/h))/(1 + s/(wc*h));
+h = 1.2;
+H_lead = 1/h*(1 + s/(wc/h))/(1 + s/(wc*h));
- Kd_dvf = diag(1./abs(diag(freqresp(1/s*Gc_dvf, wc)))) .* H_lead .* 1/s;
+Kd_dvf = diag(1./abs(diag(freqresp(1/s*Gc_dvf, wc)))) .* H_lead .* 1/s;
K_hac_dvf = inv(stewart.kinematics.J')*Kd_dvf;
+
K_hac_dvf = inv(stewart.kinematics.J')*Kd_dvf;
1.6.3 Obtained Performance
+1.6.3 Obtained Performance
controller = initializeController('type', 'open-loop');
- [T_ol, T_norm_ol, freqs] = computeTransmissibility();
- [C_ol, C_norm_ol, ~] = computeCompliance();
+
controller = initializeController('type', 'open-loop');
+[T_ol, T_norm_ol, freqs] = computeTransmissibility();
+[C_ol, C_norm_ol, ~] = computeCompliance();
controller = initializeController('type', 'dvf');
- [T_dvf, T_norm_dvf, ~] = computeTransmissibility();
- [C_dvf, C_norm_dvf, ~] = computeCompliance();
+
controller = initializeController('type', 'dvf');
+[T_dvf, T_norm_dvf, ~] = computeTransmissibility();
+[C_dvf, C_norm_dvf, ~] = computeCompliance();
controller = initializeController('type', 'hac-dvf');
- [T_hac_dvf, T_norm_hac_dvf, ~] = computeTransmissibility();
- [C_hac_dvf, C_norm_hac_dvf, ~] = computeCompliance();
+
controller = initializeController('type', 'hac-dvf');
+[T_hac_dvf, T_norm_hac_dvf, ~] = computeTransmissibility();
+[C_hac_dvf, C_norm_hac_dvf, ~] = computeCompliance();
1.7 HAC - IFF
+1.7 HAC - IFF
1.7.1 Plant
+1.7.1 Plant
1.7.2 Controller Design
+1.7.2 Controller Design
wc = 2*pi*300; % Wanted Bandwidth [rad/s]
+
wc = 2*pi*300; % Wanted Bandwidth [rad/s]
- h = 1.2;
- H_lead = 1/h*(1 + s/(wc/h))/(1 + s/(wc*h));
+h = 1.2;
+H_lead = 1/h*(1 + s/(wc/h))/(1 + s/(wc*h));
- Kd_iff = diag(1./abs(diag(freqresp(1/s*Gc_iff, wc)))) .* H_lead .* 1/s;
+Kd_iff = diag(1./abs(diag(freqresp(1/s*Gc_iff, wc)))) .* H_lead .* 1/s;
K_hac_iff = inv(stewart.kinematics.J')*Kd_iff;
+
K_hac_iff = inv(stewart.kinematics.J')*Kd_iff;
1.7.3 Obtained Performance
+1.7.3 Obtained Performance
controller = initializeController('type', 'open-loop');
- [T_ol, T_norm_ol, freqs] = computeTransmissibility();
- [C_ol, C_norm_ol, ~] = computeCompliance();
+
controller = initializeController('type', 'open-loop');
+[T_ol, T_norm_ol, freqs] = computeTransmissibility();
+[C_ol, C_norm_ol, ~] = computeCompliance();
controller = initializeController('type', 'iff');
- [T_iff, T_norm_iff, ~] = computeTransmissibility();
- [C_iff, C_norm_iff, ~] = computeCompliance();
+
controller = initializeController('type', 'iff');
+[T_iff, T_norm_iff, ~] = computeTransmissibility();
+[C_iff, C_norm_iff, ~] = computeCompliance();
controller = initializeController('type', 'hac-iff');
- [T_hac_iff, T_norm_hac_iff, ~] = computeTransmissibility();
- [C_hac_iff, C_norm_hac_iff, ~] = computeCompliance();
+
controller = initializeController('type', 'hac-iff');
+[T_hac_iff, T_norm_hac_iff, ~] = computeTransmissibility();
+[C_hac_iff, C_norm_hac_iff, ~] = computeCompliance();
2.1 Initialization
+2.1 Initialization
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart);
- stewart = initializeStrutDynamics(stewart);
- stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical');
- stewart = initializeCylindricalPlatforms(stewart);
- stewart = initializeCylindricalStruts(stewart);
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeInertialSensor(stewart, 'type', 'none');
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart);
+stewart = initializeStrutDynamics(stewart);
+stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical');
+stewart = initializeCylindricalPlatforms(stewart);
+stewart = initializeCylindricalStruts(stewart);
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeInertialSensor(stewart, 'type', 'none');
ground = initializeGround('type', 'rigid', 'rot_point', stewart.platform_F.FO_A);
- payload = initializePayload('type', 'none');
+
ground = initializeGround('type', 'rigid', 'rot_point', stewart.platform_F.FO_A);
+payload = initializePayload('type', 'none');
2.2 Identification
+2.2 Identification
2.2.1 HAC - Without LAC
+2.2.1 HAC - Without LAC
controller = initializeController('type', 'open-loop');
+
controller = initializeController('type', 'open-loop');
%% Name of the Simulink File
- mdl = 'stewart_platform_model';
+
%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Controller'], 1, 'input'); io_i = io_i + 1; % Actuator Force Inputs [N]
- io(io_i) = linio([mdl, '/Absolute Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Absolute Sensor [m, rad]
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Controller'], 1, 'input'); io_i = io_i + 1; % Actuator Force Inputs [N]
+io(io_i) = linio([mdl, '/Absolute Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Absolute Sensor [m, rad]
- %% Run the linearization
- G_ol = linearize(mdl, io);
- G_ol.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
- G_ol.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
+%% Run the linearization
+G_ol = linearize(mdl, io);
+G_ol.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
+G_ol.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
2.2.2 HAC - DVF
+2.2.2 HAC - DVF
controller = initializeController('type', 'dvf');
- K_dvf = -1e4*s/(1+s/2/pi/5000)*eye(6);
+
controller = initializeController('type', 'dvf');
+K_dvf = -1e4*s/(1+s/2/pi/5000)*eye(6);
%% Name of the Simulink File
- mdl = 'stewart_platform_model';
+
%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Controller'], 1, 'input'); io_i = io_i + 1; % Actuator Force Inputs [N]
- io(io_i) = linio([mdl, '/Absolute Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Absolute Sensor [m, rad]
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Controller'], 1, 'input'); io_i = io_i + 1; % Actuator Force Inputs [N]
+io(io_i) = linio([mdl, '/Absolute Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Absolute Sensor [m, rad]
- %% Run the linearization
- G_dvf = linearize(mdl, io);
- G_dvf.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
- G_dvf.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
+%% Run the linearization
+G_dvf = linearize(mdl, io);
+G_dvf.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
+G_dvf.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
2.2.3 Cartesian Frame
Gc_ol = minreal(G_ol)/stewart.kinematics.J';
- Gc_ol.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
+
Gc_ol = minreal(G_ol)/stewart.kinematics.J';
+Gc_ol.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
- Gc_dvf = minreal(G_dvf)/stewart.kinematics.J';
- Gc_dvf.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
+Gc_dvf = minreal(G_dvf)/stewart.kinematics.J';
+Gc_dvf.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
2.3 Singular Value Decomposition
freqs = logspace(1, 4, 1000);
+
freqs = logspace(1, 4, 1000);
- U_ol = zeros(6,6,length(freqs));
- S_ol = zeros(6,length(freqs));
- V_ol = zeros(6,6,length(freqs));
+U_ol = zeros(6,6,length(freqs));
+S_ol = zeros(6,length(freqs));
+V_ol = zeros(6,6,length(freqs));
- U_dvf = zeros(6,6,length(freqs));
- S_dvf = zeros(6,length(freqs));
- V_dvf = zeros(6,6,length(freqs));
+U_dvf = zeros(6,6,length(freqs));
+S_dvf = zeros(6,length(freqs));
+V_dvf = zeros(6,6,length(freqs));
- for i = 1:length(freqs)
+for i = 1:length(freqs)
[U,S,V] = svd(freqresp(Gc_ol, freqs(i), 'Hz'));
U_ol(:,:,i) = U;
S_ol(:,i) = diag(S);
@@ -746,7 +746,7 @@ The rotation point of the ground is located at the origin of frame \(\{A\}\).
U_dvf(:,:,i) = U;
S_dvf(:,i) = diag(S);
V_dvf(:,:,i) = V;
- end
+end
3.1 Initialization
+3.1 Initialization
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart);
- stewart = initializeStrutDynamics(stewart);
- stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical');
- stewart = initializeCylindricalPlatforms(stewart);
- stewart = initializeCylindricalStruts(stewart);
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeInertialSensor(stewart, 'type', 'none');
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart);
+stewart = initializeStrutDynamics(stewart);
+stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical');
+stewart = initializeCylindricalPlatforms(stewart);
+stewart = initializeCylindricalStruts(stewart);
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeInertialSensor(stewart, 'type', 'none');
ground = initializeGround('type', 'rigid', 'rot_point', stewart.platform_F.FO_A);
- payload = initializePayload('type', 'none');
+
ground = initializeGround('type', 'rigid', 'rot_point', stewart.platform_F.FO_A);
+payload = initializePayload('type', 'none');
3.2 Identification
+3.2 Identification
controller = initializeController('type', 'dvf');
- K_dvf = -1e4*s/(1+s/2/pi/5000)*eye(6);
+
controller = initializeController('type', 'dvf');
+K_dvf = -1e4*s/(1+s/2/pi/5000)*eye(6);
%% Name of the Simulink File
- mdl = 'stewart_platform_model';
+
%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Controller'], 1, 'input'); io_i = io_i + 1; % Actuator Force Inputs [N]
- io(io_i) = linio([mdl, '/Absolute Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Absolute Sensor [m, rad]
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Controller'], 1, 'input'); io_i = io_i + 1; % Actuator Force Inputs [N]
+io(io_i) = linio([mdl, '/Absolute Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Absolute Sensor [m, rad]
- %% Run the linearization
- G_dvf = linearize(mdl, io);
- G_dvf.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
- G_dvf.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
+%% Run the linearization
+G_dvf = linearize(mdl, io);
+G_dvf.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
+G_dvf.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
W1 = inv(freqresp(G_dvf, 0));
+
W1 = inv(freqresp(G_dvf, 0));
Gs = G_dvf*W1;
+
Gs = G_dvf*W1;
wc = 2*pi*300; % Wanted Bandwidth [rad/s]
+
wc = 2*pi*300; % Wanted Bandwidth [rad/s]
- h = 1.5;
- H_lead = 1/h*(1 + s/(wc/h))/(1 + s/(wc*h));
+h = 1.5;
+H_lead = 1/h*(1 + s/(wc/h))/(1 + s/(wc*h));
- Ks_dvf = diag(1./abs(diag(freqresp(1/s*Gs, wc)))) .* H_lead .* 1/s;
+Ks_dvf = diag(1./abs(diag(freqresp(1/s*Gs, wc)))) .* H_lead .* 1/s;
K_hac_dvf = W1 * Ks_dvf;
+
K_hac_dvf = W1 * Ks_dvf;
3.3.3 Results
+3.3.3 Results
controller = initializeController('type', 'open-loop');
- [T_ol, T_norm_ol, freqs] = computeTransmissibility();
- [C_ol, C_norm_ol, ~] = computeCompliance();
+
controller = initializeController('type', 'open-loop');
+[T_ol, T_norm_ol, freqs] = computeTransmissibility();
+[C_ol, C_norm_ol, ~] = computeCompliance();
controller = initializeController('type', 'hac-dvf');
- [T_hac_dvf, T_norm_hac_dvf, ~] = computeTransmissibility();
- [C_hac_dvf, C_norm_hac_dvf, ~] = computeCompliance();
+
controller = initializeController('type', 'hac-dvf');
+[T_hac_dvf, T_norm_hac_dvf, ~] = computeTransmissibility();
+[C_hac_dvf, C_norm_hac_dvf, ~] = computeCompliance();
4 Time Domain Simulation
4.1 Initialization
+4.1 Initialization
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart);
- stewart = initializeStrutDynamics(stewart);
- stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical');
- stewart = initializeCylindricalPlatforms(stewart);
- stewart = initializeCylindricalStruts(stewart);
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeInertialSensor(stewart, 'type', 'none');
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart);
+stewart = initializeStrutDynamics(stewart);
+stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical');
+stewart = initializeCylindricalPlatforms(stewart);
+stewart = initializeCylindricalStruts(stewart);
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeInertialSensor(stewart, 'type', 'none');
ground = initializeGround('type', 'rigid', 'rot_point', stewart.platform_F.FO_A);
- payload = initializePayload('type', 'none');
+
ground = initializeGround('type', 'rigid', 'rot_point', stewart.platform_F.FO_A);
+payload = initializePayload('type', 'none');
load('./mat/motion_error_ol.mat', 'Eg')
+
load('./mat/motion_error_ol.mat', 'Eg')
4.2 HAC IFF
controller = initializeController('type', 'iff');
- K_iff = -(1e4/s)*eye(6);
+
controller = initializeController('type', 'iff');
+K_iff = -(1e4/s)*eye(6);
- %% Name of the Simulink File
- mdl = 'stewart_platform_model';
+%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Controller'], 1, 'input'); io_i = io_i + 1; % Actuator Force Inputs [N]
- io(io_i) = linio([mdl, '/Absolute Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Absolute Sensor [m, rad]
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Controller'], 1, 'input'); io_i = io_i + 1; % Actuator Force Inputs [N]
+io(io_i) = linio([mdl, '/Absolute Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Absolute Sensor [m, rad]
- %% Run the linearization
- G_iff = linearize(mdl, io);
- G_iff.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
- G_iff.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
+%% Run the linearization
+G_iff = linearize(mdl, io);
+G_iff.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
+G_iff.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
- Gc_iff = minreal(G_iff)/stewart.kinematics.J';
- Gc_iff.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
+Gc_iff = minreal(G_iff)/stewart.kinematics.J';
+Gc_iff.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
wc = 2*pi*100; % Wanted Bandwidth [rad/s]
+
wc = 2*pi*100; % Wanted Bandwidth [rad/s]
- h = 1.2;
- H_lead = 1/h*(1 + s/(wc/h))/(1 + s/(wc*h));
+h = 1.2;
+H_lead = 1/h*(1 + s/(wc/h))/(1 + s/(wc*h));
- Kd_iff = diag(1./abs(diag(freqresp(1/s*Gc_iff, wc)))) .* H_lead .* 1/s;
- K_hac_iff = inv(stewart.kinematics.J')*Kd_iff;
+Kd_iff = diag(1./abs(diag(freqresp(1/s*Gc_iff, wc)))) .* H_lead .* 1/s;
+K_hac_iff = inv(stewart.kinematics.J')*Kd_iff;
controller = initializeController('type', 'hac-iff');
+
controller = initializeController('type', 'hac-iff');
4.3 HAC-DVF
controller = initializeController('type', 'dvf');
- K_dvf = -1e4*s/(1+s/2/pi/5000)*eye(6);
+
controller = initializeController('type', 'dvf');
+K_dvf = -1e4*s/(1+s/2/pi/5000)*eye(6);
- %% Name of the Simulink File
- mdl = 'stewart_platform_model';
+%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Controller'], 1, 'input'); io_i = io_i + 1; % Actuator Force Inputs [N]
- io(io_i) = linio([mdl, '/Absolute Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Absolute Sensor [m, rad]
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Controller'], 1, 'input'); io_i = io_i + 1; % Actuator Force Inputs [N]
+io(io_i) = linio([mdl, '/Absolute Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Absolute Sensor [m, rad]
- %% Run the linearization
- G_dvf = linearize(mdl, io);
- G_dvf.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
- G_dvf.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
+%% Run the linearization
+G_dvf = linearize(mdl, io);
+G_dvf.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
+G_dvf.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
- Gc_dvf = minreal(G_dvf)/stewart.kinematics.J';
- Gc_dvf.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
+Gc_dvf = minreal(G_dvf)/stewart.kinematics.J';
+Gc_dvf.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
wc = 2*pi*100; % Wanted Bandwidth [rad/s]
+
wc = 2*pi*100; % Wanted Bandwidth [rad/s]
- h = 1.2;
- H_lead = 1/h*(1 + s/(wc/h))/(1 + s/(wc*h));
+h = 1.2;
+H_lead = 1/h*(1 + s/(wc/h))/(1 + s/(wc*h));
- Kd_dvf = diag(1./abs(diag(freqresp(1/s*Gc_dvf, wc)))) .* H_lead .* 1/s;
+Kd_dvf = diag(1./abs(diag(freqresp(1/s*Gc_dvf, wc)))) .* H_lead .* 1/s;
- K_hac_dvf = inv(stewart.kinematics.J')*Kd_dvf;
+K_hac_dvf = inv(stewart.kinematics.J')*Kd_dvf;
controller = initializeController('type', 'hac-dvf');
+
controller = initializeController('type', 'hac-dvf');
4.4 Results
+4.4 Results
figure;
- subplot(1, 2, 1);
- hold on;
- plot(Eg.Time, Eg.Data(:, 1), 'DisplayName', 'X');
- plot(Eg.Time, Eg.Data(:, 2), 'DisplayName', 'Y');
- plot(Eg.Time, Eg.Data(:, 3), 'DisplayName', 'Z');
- hold off;
- xlabel('Time [s]');
- ylabel('Position error [m]');
- legend();
+
figure;
+subplot(1, 2, 1);
+hold on;
+plot(Eg.Time, Eg.Data(:, 1), 'DisplayName', 'X');
+plot(Eg.Time, Eg.Data(:, 2), 'DisplayName', 'Y');
+plot(Eg.Time, Eg.Data(:, 3), 'DisplayName', 'Z');
+hold off;
+xlabel('Time [s]');
+ylabel('Position error [m]');
+legend();
- subplot(1, 2, 2);
- hold on;
- plot(simout.Xa.Time, simout.Xa.Data(:, 1));
- plot(simout.Xa.Time, simout.Xa.Data(:, 2));
- plot(simout.Xa.Time, simout.Xa.Data(:, 3));
- hold off;
- xlabel('Time [s]');
- ylabel('Orientation error [rad]');
+subplot(1, 2, 2);
+hold on;
+plot(simout.Xa.Time, simout.Xa.Data(:, 1));
+plot(simout.Xa.Time, simout.Xa.Data(:, 2));
+plot(simout.Xa.Time, simout.Xa.Data(:, 3));
+hold off;
+xlabel('Time [s]');
+ylabel('Orientation error [rad]');
Function description
function [controller] = initializeController(args)
- % initializeController - Initialize the Controller
- %
- % Syntax: [] = initializeController(args)
- %
- % Inputs:
- % - args - Can have the following fields:
+
function [controller] = initializeController(args)
+% initializeController - Initialize the Controller
+%
+% Syntax: [] = initializeController(args)
+%
+% Inputs:
+% - args - Can have the following fields:
Optional Parameters
arguments
+
arguments
args.type char {mustBeMember(args.type, {'open-loop', 'iff', 'dvf', 'hac-iff', 'hac-dvf', 'ref-track-L', 'ref-track-X', 'ref-track-hac-dvf'})} = 'open-loop'
- end
+end
Structure initialization
controller = struct();
+
controller = struct();
Add Type
switch args.type
- case 'open-loop'
- controller.type = 0;
- case 'iff'
- controller.type = 1;
- case 'dvf'
- controller.type = 2;
- case 'hac-iff'
- controller.type = 3;
- case 'hac-dvf'
- controller.type = 4;
- case 'ref-track-L'
- controller.type = 5;
- case 'ref-track-X'
- controller.type = 6;
- case 'ref-track-hac-dvf'
- controller.type = 7;
- end
+
switch args.type
+ case 'open-loop'
+ controller.type = 0;
+ case 'iff'
+ controller.type = 1;
+ case 'dvf'
+ controller.type = 2;
+ case 'hac-iff'
+ controller.type = 3;
+ case 'hac-dvf'
+ controller.type = 4;
+ case 'ref-track-L'
+ controller.type = 5;
+ case 'ref-track-X'
+ controller.type = 6;
+ case 'ref-track-hac-dvf'
+ controller.type = 7;
+end
H = 100e-3; % height of the Stewart platform [m]
- MO_B = -H/2; % Position {B} with respect to {M} [m]
- Hc = H; % Size of the useful part of the cube [m]
- FOc = H + MO_B; % Center of the cube with respect to {F}
+
H = 100e-3; % height of the Stewart platform [m]
+MO_B = -H/2; % Position {B} with respect to {M} [m]
+Hc = H; % Size of the useful part of the cube [m]
+FOc = H + MO_B; % Center of the cube with respect to {F}
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', H, 'MO_B', MO_B);
- stewart = generateCubicConfiguration(stewart, 'Hc', Hc, 'FOc', FOc, 'FHa', 0, 'MHb', 0);
- stewart = computeJointsPose(stewart);
- stewart = initializeStrutDynamics(stewart, 'K', ones(6,1));
- stewart = computeJacobian(stewart);
- stewart = initializeCylindricalPlatforms(stewart, 'Fpr', 175e-3, 'Mpr', 150e-3);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', H, 'MO_B', MO_B);
+stewart = generateCubicConfiguration(stewart, 'Hc', Hc, 'FOc', FOc, 'FHa', 0, 'MHb', 0);
+stewart = computeJointsPose(stewart);
+stewart = initializeStrutDynamics(stewart, 'K', ones(6,1));
+stewart = computeJacobian(stewart);
+stewart = initializeCylindricalPlatforms(stewart, 'Fpr', 175e-3, 'Mpr', 150e-3);
H = 100e-3; % height of the Stewart platform [m]
- MO_B = 20e-3; % Position {B} with respect to {M} [m]
- Hc = H; % Size of the useful part of the cube [m]
- FOc = H/2; % Center of the cube with respect to {F}
+
H = 100e-3; % height of the Stewart platform [m]
+MO_B = 20e-3; % Position {B} with respect to {M} [m]
+Hc = H; % Size of the useful part of the cube [m]
+FOc = H/2; % Center of the cube with respect to {F}
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', H, 'MO_B', MO_B);
- stewart = generateCubicConfiguration(stewart, 'Hc', Hc, 'FOc', FOc, 'FHa', 0, 'MHb', 0);
- stewart = computeJointsPose(stewart);
- stewart = initializeStrutDynamics(stewart, 'K', ones(6,1));
- stewart = computeJacobian(stewart);
- stewart = initializeCylindricalPlatforms(stewart, 'Fpr', 175e-3, 'Mpr', 150e-3);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', H, 'MO_B', MO_B);
+stewart = generateCubicConfiguration(stewart, 'Hc', Hc, 'FOc', FOc, 'FHa', 0, 'MHb', 0);
+stewart = computeJointsPose(stewart);
+stewart = initializeStrutDynamics(stewart, 'K', ones(6,1));
+stewart = computeJacobian(stewart);
+stewart = initializeCylindricalPlatforms(stewart, 'Fpr', 175e-3, 'Mpr', 150e-3);
H = 80e-3; % height of the Stewart platform [m]
- MO_B = -30e-3; % Position {B} with respect to {M} [m]
- Hc = 100e-3; % Size of the useful part of the cube [m]
- FOc = H + MO_B; % Center of the cube with respect to {F}
+
H = 80e-3; % height of the Stewart platform [m]
+MO_B = -30e-3; % Position {B} with respect to {M} [m]
+Hc = 100e-3; % Size of the useful part of the cube [m]
+FOc = H + MO_B; % Center of the cube with respect to {F}
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', H, 'MO_B', MO_B);
- stewart = generateCubicConfiguration(stewart, 'Hc', Hc, 'FOc', FOc, 'FHa', 0, 'MHb', 0);
- stewart = computeJointsPose(stewart);
- stewart = initializeStrutDynamics(stewart, 'K', ones(6,1));
- stewart = computeJacobian(stewart);
- stewart = initializeCylindricalPlatforms(stewart, 'Fpr', 175e-3, 'Mpr', 150e-3);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', H, 'MO_B', MO_B);
+stewart = generateCubicConfiguration(stewart, 'Hc', Hc, 'FOc', FOc, 'FHa', 0, 'MHb', 0);
+stewart = computeJointsPose(stewart);
+stewart = initializeStrutDynamics(stewart, 'K', ones(6,1));
+stewart = computeJacobian(stewart);
+stewart = initializeCylindricalPlatforms(stewart, 'Fpr', 175e-3, 'Mpr', 150e-3);
H = 100e-3; % height of the Stewart platform [m]
- MO_B = -H/2; % Position {B} with respect to {M} [m]
- Hc = 1.5*H; % Size of the useful part of the cube [m]
- FOc = H/2 + 10e-3; % Center of the cube with respect to {F}
+
H = 100e-3; % height of the Stewart platform [m]
+MO_B = -H/2; % Position {B} with respect to {M} [m]
+Hc = 1.5*H; % Size of the useful part of the cube [m]
+FOc = H/2 + 10e-3; % Center of the cube with respect to {F}
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', H, 'MO_B', MO_B);
- stewart = generateCubicConfiguration(stewart, 'Hc', Hc, 'FOc', FOc, 'FHa', 0, 'MHb', 0);
- stewart = computeJointsPose(stewart);
- stewart = initializeStrutDynamics(stewart, 'K', ones(6,1));
- stewart = computeJacobian(stewart);
- stewart = initializeCylindricalPlatforms(stewart, 'Fpr', 215e-3, 'Mpr', 195e-3);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', H, 'MO_B', MO_B);
+stewart = generateCubicConfiguration(stewart, 'Hc', Hc, 'FOc', FOc, 'FHa', 0, 'MHb', 0);
+stewart = computeJointsPose(stewart);
+stewart = initializeStrutDynamics(stewart, 'K', ones(6,1));
+stewart = computeJacobian(stewart);
+stewart = initializeCylindricalPlatforms(stewart, 'Fpr', 215e-3, 'Mpr', 195e-3);
1.5 Conclusion
+1.5 Conclusion
H = 100e-3; % height of the Stewart platform [m]
- MO_B = 20e-3; % Position {B} with respect to {M} [m]
+
H = 100e-3; % height of the Stewart platform [m]
+MO_B = 20e-3; % Position {B} with respect to {M} [m]
Hc = 0.4*H; % Size of the useful part of the cube [m]
- FOc = H + MO_B; % Center of the cube with respect to {F}
+
Hc = 0.4*H; % Size of the useful part of the cube [m]
+FOc = H + MO_B; % Center of the cube with respect to {F}
Hc = 1.5*H; % Size of the useful part of the cube [m]
- FOc = H + MO_B; % Center of the cube with respect to {F}
+
Hc = 1.5*H; % Size of the useful part of the cube [m]
+FOc = H + MO_B; % Center of the cube with respect to {F}
Hc = 2.5*H; % Size of the useful part of the cube [m]
- FOc = H + MO_B; % Center of the cube with respect to {F}
+
Hc = 2.5*H; % Size of the useful part of the cube [m]
+FOc = H + MO_B; % Center of the cube with respect to {F}
2.3 Conclusion
+2.3 Conclusion
Hcs = 1e-3*[250:20:350]; % Heights for the Cube [m]
- Ks = zeros(6, 6, length(Hcs));
+
Hcs = 1e-3*[250:20:350]; % Heights for the Cube [m]
+Ks = zeros(6, 6, length(Hcs));
H = 100e-3; % height of the Stewart platform [m]
+
H = 100e-3; % height of the Stewart platform [m]
MO_B = -50e-3; % Position {B} with respect to {M} [m]
- FOc = H + MO_B; % Center of the cube with respect to {F}
+
MO_B = -50e-3; % Position {B} with respect to {M} [m]
+FOc = H + MO_B; % Center of the cube with respect to {F}
3.2 Conclusion
+3.2 Conclusion
H = 200e-3; % height of the Stewart platform [m]
- MO_B = -10e-3; % Position {B} with respect to {M} [m]
+
H = 200e-3; % height of the Stewart platform [m]
+MO_B = -10e-3; % Position {B} with respect to {M} [m]
Hc = 2.5*H; % Size of the useful part of the cube [m]
- FOc = H + MO_B; % Center of the cube with respect to {F}
+
Hc = 2.5*H; % Size of the useful part of the cube [m]
+FOc = H + MO_B; % Center of the cube with respect to {F}
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', H, 'MO_B', MO_B);
- stewart = generateCubicConfiguration(stewart, 'Hc', Hc, 'FOc', FOc, 'FHa', 25e-3, 'MHb', 25e-3);
- stewart = computeJointsPose(stewart);
- stewart = initializeStrutDynamics(stewart, 'K', 1e6*ones(6,1), 'C', 1e1*ones(6,1));
- stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical');
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', H, 'MO_B', MO_B);
+stewart = generateCubicConfiguration(stewart, 'Hc', Hc, 'FOc', FOc, 'FHa', 25e-3, 'MHb', 25e-3);
+stewart = computeJointsPose(stewart);
+stewart = initializeStrutDynamics(stewart, 'K', 1e6*ones(6,1), 'C', 1e1*ones(6,1));
+stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical');
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
stewart = initializeCylindricalPlatforms(stewart, 'Fpr', 1.2*max(vecnorm(stewart.platform_F.Fa)), ...
- 'Mpm', 10, ...
- 'Mph', 20e-3, ...
- 'Mpr', 1.2*max(vecnorm(stewart.platform_M.Mb)));
+
stewart = initializeCylindricalPlatforms(stewart, 'Fpr', 1.2*max(vecnorm(stewart.platform_F.Fa)), ...
+ 'Mpm', 10, ...
+ 'Mph', 20e-3, ...
+ 'Mpr', 1.2*max(vecnorm(stewart.platform_M.Mb)));
stewart = initializeCylindricalStruts(stewart, 'Fsm', 1e-3, 'Msm', 1e-3);
- stewart = initializeInertialSensor(stewart);
+
stewart = initializeCylindricalStruts(stewart, 'Fsm', 1e-3, 'Msm', 1e-3);
+stewart = initializeInertialSensor(stewart);
ground = initializeGround('type', 'none');
- payload = initializePayload('type', 'none');
- controller = initializeController('type', 'open-loop');
+
ground = initializeGround('type', 'none');
+payload = initializePayload('type', 'none');
+controller = initializeController('type', 'open-loop');
open('stewart_platform_model.slx')
+
open('stewart_platform_model.slx')
- %% Options for Linearized
- options = linearizeOptions;
- options.SampleTime = 0;
+%% Options for Linearized
+options = linearizeOptions;
+options.SampleTime = 0;
- %% Name of the Simulink File
- mdl = 'stewart_platform_model';
+%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
- io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'dLm'); io_i = io_i + 1; % Relative Displacement Outputs [m]
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
+io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'dLm'); io_i = io_i + 1; % Relative Displacement Outputs [m]
- %% Run the linearization
- G = linearize(mdl, io, options);
- G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
- G.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6'};
+%% Run the linearization
+G = linearize(mdl, io, options);
+G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
+G.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6'};
Gc = inv(stewart.kinematics.J)*G*inv(stewart.kinematics.J');
- Gc = inv(stewart.kinematics.J)*G*stewart.kinematics.J;
- Gc.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
- Gc.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
+
Gc = inv(stewart.kinematics.J)*G*inv(stewart.kinematics.J');
+Gc = inv(stewart.kinematics.J)*G*stewart.kinematics.J;
+Gc.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
+Gc.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
H = 200e-3; % height of the Stewart platform [m]
- MO_B = -100e-3; % Position {B} with respect to {M} [m]
+
H = 200e-3; % height of the Stewart platform [m]
+MO_B = -100e-3; % Position {B} with respect to {M} [m]
Hc = 2.5*H; % Size of the useful part of the cube [m]
- FOc = H + MO_B; % Center of the cube with respect to {F}
+
Hc = 2.5*H; % Size of the useful part of the cube [m]
+FOc = H + MO_B; % Center of the cube with respect to {F}
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', H, 'MO_B', MO_B);
- stewart = generateCubicConfiguration(stewart, 'Hc', Hc, 'FOc', FOc, 'FHa', 25e-3, 'MHb', 25e-3);
- stewart = computeJointsPose(stewart);
- stewart = initializeStrutDynamics(stewart, 'K', 1e6*ones(6,1), 'C', 1e1*ones(6,1));
- stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical');
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', H, 'MO_B', MO_B);
+stewart = generateCubicConfiguration(stewart, 'Hc', Hc, 'FOc', FOc, 'FHa', 25e-3, 'MHb', 25e-3);
+stewart = computeJointsPose(stewart);
+stewart = initializeStrutDynamics(stewart, 'K', 1e6*ones(6,1), 'C', 1e1*ones(6,1));
+stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical');
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
stewart = initializeCylindricalPlatforms(stewart, 'Fpr', 1.2*max(vecnorm(stewart.platform_F.Fa)), ...
- 'Mpm', 10, ...
- 'Mph', 20e-3, ...
- 'Mpr', 1.2*max(vecnorm(stewart.platform_M.Mb)));
+
stewart = initializeCylindricalPlatforms(stewart, 'Fpr', 1.2*max(vecnorm(stewart.platform_F.Fa)), ...
+ 'Mpm', 10, ...
+ 'Mph', 20e-3, ...
+ 'Mpr', 1.2*max(vecnorm(stewart.platform_M.Mb)));
stewart = initializeCylindricalStruts(stewart, 'Fsm', 1e-3, 'Msm', 1e-3);
- stewart = initializeInertialSensor(stewart);
+
stewart = initializeCylindricalStruts(stewart, 'Fsm', 1e-3, 'Msm', 1e-3);
+stewart = initializeInertialSensor(stewart);
ground = initializeGround('type', 'none');
- payload = initializePayload('type', 'none');
- controller = initializeController('type', 'open-loop');
+
ground = initializeGround('type', 'none');
+payload = initializePayload('type', 'none');
+controller = initializeController('type', 'open-loop');
open('stewart_platform_model.slx')
+
open('stewart_platform_model.slx')
- %% Options for Linearized
- options = linearizeOptions;
- options.SampleTime = 0;
+%% Options for Linearized
+options = linearizeOptions;
+options.SampleTime = 0;
- %% Name of the Simulink File
- mdl = 'stewart_platform_model';
+%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
- io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'dLm'); io_i = io_i + 1; % Relative Displacement Outputs [m]
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
+io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'dLm'); io_i = io_i + 1; % Relative Displacement Outputs [m]
- %% Run the linearization
- G = linearize(mdl, io, options);
- G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
- G.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6'};
+%% Run the linearization
+G = linearize(mdl, io, options);
+G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
+G.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6'};
Gc = inv(stewart.kinematics.J)*G*inv(stewart.kinematics.J');
- Gc.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
- Gc.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
+
Gc = inv(stewart.kinematics.J)*G*inv(stewart.kinematics.J');
+Gc.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
+Gc.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
4.3 Conclusion
+4.3 Conclusion
H = 200e-3; % height of the Stewart platform [m]
- MO_B = -10e-3; % Position {B} with respect to {M} [m]
- Hc = 2.5*H; % Size of the useful part of the cube [m]
- FOc = H + MO_B; % Center of the cube with respect to {F}
+
H = 200e-3; % height of the Stewart platform [m]
+MO_B = -10e-3; % Position {B} with respect to {M} [m]
+Hc = 2.5*H; % Size of the useful part of the cube [m]
+FOc = H + MO_B; % Center of the cube with respect to {F}
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', H, 'MO_B', MO_B);
- stewart = generateCubicConfiguration(stewart, 'Hc', Hc, 'FOc', FOc, 'FHa', 25e-3, 'MHb', 25e-3);
- stewart = computeJointsPose(stewart);
- stewart = initializeStrutDynamics(stewart, 'K', 1e6*ones(6,1), 'C', 1e1*ones(6,1));
- stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical');
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeCylindricalPlatforms(stewart, 'Fpr', 1.2*max(vecnorm(stewart.platform_F.Fa)), ...
- 'Mpm', 10, ...
- 'Mph', 20e-3, ...
- 'Mpr', 1.2*max(vecnorm(stewart.platform_M.Mb)));
- stewart = initializeCylindricalStruts(stewart, 'Fsm', 1e-3, 'Msm', 1e-3);
- stewart = initializeInertialSensor(stewart);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', H, 'MO_B', MO_B);
+stewart = generateCubicConfiguration(stewart, 'Hc', Hc, 'FOc', FOc, 'FHa', 25e-3, 'MHb', 25e-3);
+stewart = computeJointsPose(stewart);
+stewart = initializeStrutDynamics(stewart, 'K', 1e6*ones(6,1), 'C', 1e1*ones(6,1));
+stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical');
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeCylindricalPlatforms(stewart, 'Fpr', 1.2*max(vecnorm(stewart.platform_F.Fa)), ...
+ 'Mpm', 10, ...
+ 'Mph', 20e-3, ...
+ 'Mpr', 1.2*max(vecnorm(stewart.platform_M.Mb)));
+stewart = initializeCylindricalStruts(stewart, 'Fsm', 1e-3, 'Msm', 1e-3);
+stewart = initializeInertialSensor(stewart);
ground = initializeGround('type', 'none');
- payload = initializePayload('type', 'none');
- controller = initializeController('type', 'open-loop');
+
ground = initializeGround('type', 'none');
+payload = initializePayload('type', 'none');
+controller = initializeController('type', 'open-loop');
disturbances = initializeDisturbances();
- references = initializeReferences(stewart);
+
disturbances = initializeDisturbances();
+references = initializeReferences(stewart);
H = 200e-3; % height of the Stewart platform [m]
- MO_B = -10e-3; % Position {B} with respect to {M} [m]
+
H = 200e-3; % height of the Stewart platform [m]
+MO_B = -10e-3; % Position {B} with respect to {M} [m]
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', H, 'MO_B', MO_B);
- stewart = generateGeneralConfiguration(stewart, 'FR', 250e-3, 'MR', 150e-3);
- stewart = computeJointsPose(stewart);
- stewart = initializeStrutDynamics(stewart, 'K', 1e6*ones(6,1), 'C', 1e1*ones(6,1));
- stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical');
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeCylindricalPlatforms(stewart, 'Fpr', 1.2*max(vecnorm(stewart.platform_F.Fa)), ...
- 'Mpm', 10, ...
- 'Mph', 20e-3, ...
- 'Mpr', 1.2*max(vecnorm(stewart.platform_M.Mb)));
- stewart = initializeCylindricalStruts(stewart, 'Fsm', 1e-3, 'Msm', 1e-3);
- stewart = initializeInertialSensor(stewart);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', H, 'MO_B', MO_B);
+stewart = generateGeneralConfiguration(stewart, 'FR', 250e-3, 'MR', 150e-3);
+stewart = computeJointsPose(stewart);
+stewart = initializeStrutDynamics(stewart, 'K', 1e6*ones(6,1), 'C', 1e1*ones(6,1));
+stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical');
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeCylindricalPlatforms(stewart, 'Fpr', 1.2*max(vecnorm(stewart.platform_F.Fa)), ...
+ 'Mpm', 10, ...
+ 'Mph', 20e-3, ...
+ 'Mpr', 1.2*max(vecnorm(stewart.platform_M.Mb)));
+stewart = initializeCylindricalStruts(stewart, 'Fsm', 1e-3, 'Msm', 1e-3);
+stewart = initializeInertialSensor(stewart);
ground = initializeGround('type', 'none');
- payload = initializePayload('type', 'none');
- controller = initializeController('type', 'open-loop');
+
ground = initializeGround('type', 'none');
+payload = initializePayload('type', 'none');
+controller = initializeController('type', 'open-loop');
5.3 Conclusion
+5.3 Conclusion
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}
+
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}
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
+
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
stewart
structure elements
assert(isfield(stewart.geometry, 'H'), 'stewart.geometry should have attribute H')
- H = stewart.geometry.H;
+
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];
+
sx = [ 2; -1; -1];
+sy = [ 0; 1; -1];
+sz = [ 1; 1; 1];
- R = [sx, sy, sz]./vecnorm([sx, sy, sz]);
+R = [sx, sy, sz]./vecnorm([sx, sy, sz]);
- L = args.Hc*sqrt(3);
+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];
+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
+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
CSi = (CCm - CCf)./vecnorm(CCm - CCf);
+
CSi = (CCm - CCf)./vecnorm(CCm - CCf);
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;
+
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;
Populate the
stewart
structure stewart.platform_F.Fa = Fa;
- stewart.platform_M.Mb = Mb;
+
stewart.platform_F.Fa = Fa;
+stewart.platform_M.Mb = Mb;
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart);
- stewart = initializeStrutDynamics(stewart);
- stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p');
- stewart = initializeCylindricalPlatforms(stewart);
- stewart = initializeCylindricalStruts(stewart);
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeInertialSensor(stewart, 'type', 'none');
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart);
+stewart = initializeStrutDynamics(stewart);
+stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p');
+stewart = initializeCylindricalPlatforms(stewart);
+stewart = initializeCylindricalStruts(stewart);
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeInertialSensor(stewart, 'type', 'none');
ground = initializeGround('type', 'none');
- payload = initializePayload('type', 'none');
- controller = initializeController('type', 'open-loop');
+
ground = initializeGround('type', 'none');
+payload = initializePayload('type', 'none');
+controller = initializeController('type', 'open-loop');
%% Options for Linearized
- options = linearizeOptions;
- options.SampleTime = 0;
+
%% Options for Linearized
+options = linearizeOptions;
+options.SampleTime = 0;
- %% Name of the Simulink File
- mdl = 'stewart_platform_model';
+%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
- io(io_i) = linio([mdl, '/Relative Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Position/Orientation of {B} w.r.t. {A}
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
+io(io_i) = linio([mdl, '/Relative Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Position/Orientation of {B} w.r.t. {A}
- %% Run the linearization
- G = linearize(mdl, io, options);
- G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
- G.OutputName = {'Edx', 'Edy', 'Edz', 'Erx', 'Ery', 'Erz'};
+%% Run the linearization
+G = linearize(mdl, io, options);
+G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
+G.OutputName = {'Edx', 'Edy', 'Edz', 'Erx', 'Ery', 'Erz'};
Gc = minreal(G*inv(stewart.kinematics.J'));
- Gc.InputName = {'Fnx', 'Fny', 'Fnz', 'Mnx', 'Mny', 'Mnz'};
+
Gc = minreal(G*inv(stewart.kinematics.J'));
+Gc.InputName = {'Fnx', 'Fny', 'Fnz', 'Mnx', 'Mny', 'Mnz'};
%% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Disturbances'], 1, 'openinput', [], 'F_ext'); io_i = io_i + 1; % External forces/torques applied on {B}
- io(io_i) = linio([mdl, '/Relative Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Position/Orientation of {B} w.r.t. {A}
+
%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Disturbances'], 1, 'openinput', [], 'F_ext'); io_i = io_i + 1; % External forces/torques applied on {B}
+io(io_i) = linio([mdl, '/Relative Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Position/Orientation of {B} w.r.t. {A}
- %% Run the linearization
- Gd = linearize(mdl, io, options);
- Gd.InputName = {'Fex', 'Fey', 'Fez', 'Mex', 'Mey', 'Mez'};
- Gd.OutputName = {'Edx', 'Edy', 'Edz', 'Erx', 'Ery', 'Erz'};
+%% Run the linearization
+Gd = linearize(mdl, io, options);
+Gd.InputName = {'Fex', 'Fey', 'Fez', 'Mex', 'Mey', 'Mez'};
+Gd.OutputName = {'Edx', 'Edy', 'Edz', 'Erx', 'Ery', 'Erz'};
ground = initializeGround('type', 'flexible');
+
ground = initializeGround('type', 'flexible');
%% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
- io(io_i) = linio([mdl, '/Relative Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Position/Orientation of {B} w.r.t. {A}
+
%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
+io(io_i) = linio([mdl, '/Relative Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Position/Orientation of {B} w.r.t. {A}
- %% Run the linearization
- G = linearize(mdl, io, options);
- G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
- G.OutputName = {'Edx', 'Edy', 'Edz', 'Erx', 'Ery', 'Erz'};
+%% Run the linearization
+G = linearize(mdl, io, options);
+G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
+G.OutputName = {'Edx', 'Edy', 'Edz', 'Erx', 'Ery', 'Erz'};
- Gc = minreal(G*inv(stewart.kinematics.J'));
- Gc.InputName = {'Fnx', 'Fny', 'Fnz', 'Mnx', 'Mny', 'Mnz'};
+Gc = minreal(G*inv(stewart.kinematics.J'));
+Gc.InputName = {'Fnx', 'Fny', 'Fnz', 'Mnx', 'Mny', 'Mnz'};
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Disturbances'], 1, 'openinput', [], 'F_ext'); io_i = io_i + 1; % External forces/torques applied on {B}
- io(io_i) = linio([mdl, '/Relative Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Position/Orientation of {B} w.r.t. {A}
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Disturbances'], 1, 'openinput', [], 'F_ext'); io_i = io_i + 1; % External forces/torques applied on {B}
+io(io_i) = linio([mdl, '/Relative Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Position/Orientation of {B} w.r.t. {A}
- %% Run the linearization
- Gd = linearize(mdl, io, options);
- Gd.InputName = {'Fex', 'Fey', 'Fez', 'Mex', 'Mey', 'Mez'};
- Gd.OutputName = {'Edx', 'Edy', 'Edz', 'Erx', 'Ery', 'Erz'};
+%% Run the linearization
+Gd = linearize(mdl, io, options);
+Gd.InputName = {'Fex', 'Fey', 'Fez', 'Mex', 'Mey', 'Mez'};
+Gd.OutputName = {'Edx', 'Edy', 'Edz', 'Erx', 'Ery', 'Erz'};
1.3 Conclusion
+1.3 Conclusion
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart);
- stewart = initializeStrutDynamics(stewart);
- stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p');
- stewart = initializeCylindricalPlatforms(stewart);
- stewart = initializeCylindricalStruts(stewart);
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeInertialSensor(stewart, 'type', 'none');
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart);
+stewart = initializeStrutDynamics(stewart);
+stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p');
+stewart = initializeCylindricalPlatforms(stewart);
+stewart = initializeCylindricalStruts(stewart);
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeInertialSensor(stewart, 'type', 'none');
ground = initializeGround('type', 'none');
- payload = initializePayload('type', 'none');
- controller = initializeController('type', 'open-loop');
+
ground = initializeGround('type', 'none');
+payload = initializePayload('type', 'none');
+controller = initializeController('type', 'open-loop');
%% Options for Linearized
- options = linearizeOptions;
- options.SampleTime = 0;
+
%% Options for Linearized
+options = linearizeOptions;
+options.SampleTime = 0;
- %% Name of the Simulink File
- mdl = 'stewart_platform_model';
+%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
- io(io_i) = linio([mdl, '/Relative Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Position/Orientation of {B} w.r.t. {A}
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
+io(io_i) = linio([mdl, '/Relative Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Position/Orientation of {B} w.r.t. {A}
- %% Run the linearization
- G = linearize(mdl, io, options);
- G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
- G.OutputName = {'Edx', 'Edy', 'Edz', 'Erx', 'Ery', 'Erz'};
+%% Run the linearization
+G = linearize(mdl, io, options);
+G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
+G.OutputName = {'Edx', 'Edy', 'Edz', 'Erx', 'Ery', 'Erz'};
Gc = minreal(G*inv(stewart.kinematics.J'));
- Gc.InputName = {'Fnx', 'Fny', 'Fnz', 'Mnx', 'Mny', 'Mnz'};
+
Gc = minreal(G*inv(stewart.kinematics.J'));
+Gc.InputName = {'Fnx', 'Fny', 'Fnz', 'Mnx', 'Mny', 'Mnz'};
2.2 Conclusion
+2.2 Conclusion
-
-
1 Simscape Model
1.1 Flexible APA
+1.1 Flexible APA
apa = load('./mat/APA300ML.mat', 'int_xyz', 'int_i', 'n_xyz', 'n_i', 'nodes', 'M', 'K');
+
apa = load('./mat/APA300ML.mat', 'int_xyz', 'int_i', 'n_xyz', 'n_i', 'nodes', 'M', 'K');
1.2 Flexible Joint
flex_joint = load('./mat/flexor_025.mat', 'int_xyz', 'int_i', 'n_xyz', 'n_i', 'nodes', 'M', 'K');
+
flex_joint = load('./mat/flexor_025.mat', 'int_xyz', 'int_i', 'n_xyz', 'n_i', 'nodes', 'M', 'K');
1.3 Identification
+1.3 Identification
%% Options for Linearized
- options = linearizeOptions;
- options.SampleTime = 0;
+
%% Options for Linearized
+options = linearizeOptions;
+options.SampleTime = 0;
- %% Name of the Simulink File
- mdl = 'stewart_platform_model';
+%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
- io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'dLm'); io_i = io_i + 1; % Relative Displacement Outputs [m]
- io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'Taum'); io_i = io_i + 1; % Force Sensors [N]
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
+io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'dLm'); io_i = io_i + 1; % Relative Displacement Outputs [m]
+io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'Taum'); io_i = io_i + 1; % Force Sensors [N]
ground = initializeGround('type', 'none');
- payload = initializePayload('type', 'rigid', 'm', 50);
- controller = initializeController('type', 'open-loop');
+
ground = initializeGround('type', 'none');
+payload = initializePayload('type', 'rigid', 'm', 50);
+controller = initializeController('type', 'open-loop');
disturbances = initializeDisturbances();
+
disturbances = initializeDisturbances();
1.4 No Flexible Elements
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart);
- stewart = initializeAmplifiedStrutDynamics(stewart, 'Ke', 1.5e6*ones(6,1), 'Ka', 40.5e6*ones(6,1), 'K1', 0.4e6*ones(6,1));
- stewart = initializeJointDynamics(stewart, 'type_M', 'spherical_3dof', ...
- 'Kr_M', flex_joint.K(1,1)*ones(6,1), ...
- 'Ka_M', flex_joint.K(3,3)*ones(6,1), ...
- 'Kf_M', flex_joint.K(4,4)*ones(6,1), ...
- 'Kt_M', flex_joint.K(6,6)*ones(6,1), ...
- 'type_F', 'universal_3dof', ...
- 'Kr_F', flex_joint.K(1,1)*ones(6,1), ...
- 'Ka_F', flex_joint.K(3,3)*ones(6,1), ...
- 'Kf_F', flex_joint.K(4,4)*ones(6,1), ...
- 'Kt_F', flex_joint.K(6,6)*ones(6,1));
- stewart = initializeCylindricalPlatforms(stewart);
- stewart = initializeCylindricalStruts(stewart);
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeInertialSensor(stewart);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart);
+stewart = initializeAmplifiedStrutDynamics(stewart, 'Ke', 1.5e6*ones(6,1), 'Ka', 40.5e6*ones(6,1), 'K1', 0.4e6*ones(6,1));
+stewart = initializeJointDynamics(stewart, 'type_M', 'spherical_3dof', ...
+ 'Kr_M', flex_joint.K(1,1)*ones(6,1), ...
+ 'Ka_M', flex_joint.K(3,3)*ones(6,1), ...
+ 'Kf_M', flex_joint.K(4,4)*ones(6,1), ...
+ 'Kt_M', flex_joint.K(6,6)*ones(6,1), ...
+ 'type_F', 'universal_3dof', ...
+ 'Kr_F', flex_joint.K(1,1)*ones(6,1), ...
+ 'Ka_F', flex_joint.K(3,3)*ones(6,1), ...
+ 'Kf_F', flex_joint.K(4,4)*ones(6,1), ...
+ 'Kt_F', flex_joint.K(6,6)*ones(6,1));
+stewart = initializeCylindricalPlatforms(stewart);
+stewart = initializeCylindricalStruts(stewart);
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeInertialSensor(stewart);
- references = initializeReferences(stewart);
+references = initializeReferences(stewart);
%% Run the linearization
- G = linearize(mdl, io, options);
- G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
- G.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6', 'Fm1', 'Fm2', 'Fm3', 'Fm4', 'Fm5', 'Fm6'};
+
%% Run the linearization
+G = linearize(mdl, io, options);
+G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
+G.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6', 'Fm1', 'Fm2', 'Fm3', 'Fm4', 'Fm5', 'Fm6'};
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart);
- stewart = initializeAmplifiedStrutDynamics(stewart, 'Ke', 1.5e6*ones(6,1), 'Ka', 40.5e6*ones(6,1), 'K1', 0.4e6*ones(6,1));
- stewart = initializeJointDynamics(stewart, 'type_F', 'flexible', 'K_F', flex_joint.K, 'M_F', flex_joint.M, 'n_xyz_F', flex_joint.n_xyz, 'xi_F', 0.1, 'step_file_F', 'mat/flexor_ID16.STEP', 'type_M', 'flexible', 'K_M', flex_joint.K, 'M_M', flex_joint.M, 'n_xyz_M', flex_joint.n_xyz, 'xi_M', 0.1, 'step_file_M', 'mat/flexor_ID16.STEP');
- stewart = initializeCylindricalPlatforms(stewart);
- stewart = initializeCylindricalStruts(stewart);
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeInertialSensor(stewart);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart);
+stewart = initializeAmplifiedStrutDynamics(stewart, 'Ke', 1.5e6*ones(6,1), 'Ka', 40.5e6*ones(6,1), 'K1', 0.4e6*ones(6,1));
+stewart = initializeJointDynamics(stewart, 'type_F', 'flexible', 'K_F', flex_joint.K, 'M_F', flex_joint.M, 'n_xyz_F', flex_joint.n_xyz, 'xi_F', 0.1, 'step_file_F', 'mat/flexor_ID16.STEP', 'type_M', 'flexible', 'K_M', flex_joint.K, 'M_M', flex_joint.M, 'n_xyz_M', flex_joint.n_xyz, 'xi_M', 0.1, 'step_file_M', 'mat/flexor_ID16.STEP');
+stewart = initializeCylindricalPlatforms(stewart);
+stewart = initializeCylindricalStruts(stewart);
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeInertialSensor(stewart);
%% Run the linearization
- Gj = linearize(mdl, io, options);
- Gj.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
- Gj.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6', 'Fm1', 'Fm2', 'Fm3', 'Fm4', 'Fm5', 'Fm6'};
+
%% Run the linearization
+Gj = linearize(mdl, io, options);
+Gj.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
+Gj.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6', 'Fm1', 'Fm2', 'Fm3', 'Fm4', 'Fm5', 'Fm6'};
1.6 Flexible APA
+1.6 Flexible APA
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart);
- stewart = initializeFlexibleStrutDynamics(stewart, 'H', 0.03, 'K', apa.K, 'M', apa.M, 'n_xyz', apa.n_xyz, 'xi', 0.1, 'Gf', -2.65e7, 'step_file', 'mat/APA300ML.STEP');
- stewart = initializeJointDynamics(stewart, 'type_M', 'spherical_3dof', ...
- 'Kr_M', flex_joint.K(1,1)*ones(6,1), ...
- 'Ka_M', flex_joint.K(3,3)*ones(6,1), ...
- 'Kf_M', flex_joint.K(4,4)*ones(6,1), ...
- 'Kt_M', flex_joint.K(6,6)*ones(6,1), ...
- 'type_F', 'universal_3dof', ...
- 'Kr_F', flex_joint.K(1,1)*ones(6,1), ...
- 'Ka_F', flex_joint.K(3,3)*ones(6,1), ...
- 'Kf_F', flex_joint.K(4,4)*ones(6,1), ...
- 'Kt_F', flex_joint.K(6,6)*ones(6,1));
- stewart = initializeCylindricalPlatforms(stewart);
- stewart = initializeCylindricalStruts(stewart, 'type_F', 'none', 'type_M', 'none');
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeInertialSensor(stewart);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart);
+stewart = initializeFlexibleStrutDynamics(stewart, 'H', 0.03, 'K', apa.K, 'M', apa.M, 'n_xyz', apa.n_xyz, 'xi', 0.1, 'Gf', -2.65e7, 'step_file', 'mat/APA300ML.STEP');
+stewart = initializeJointDynamics(stewart, 'type_M', 'spherical_3dof', ...
+ 'Kr_M', flex_joint.K(1,1)*ones(6,1), ...
+ 'Ka_M', flex_joint.K(3,3)*ones(6,1), ...
+ 'Kf_M', flex_joint.K(4,4)*ones(6,1), ...
+ 'Kt_M', flex_joint.K(6,6)*ones(6,1), ...
+ 'type_F', 'universal_3dof', ...
+ 'Kr_F', flex_joint.K(1,1)*ones(6,1), ...
+ 'Ka_F', flex_joint.K(3,3)*ones(6,1), ...
+ 'Kf_F', flex_joint.K(4,4)*ones(6,1), ...
+ 'Kt_F', flex_joint.K(6,6)*ones(6,1));
+stewart = initializeCylindricalPlatforms(stewart);
+stewart = initializeCylindricalStruts(stewart, 'type_F', 'none', 'type_M', 'none');
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeInertialSensor(stewart);
%% Run the linearization
- Ga = -linearize(mdl, io, options);
- Ga.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
- Ga.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6', 'Fm1', 'Fm2', 'Fm3', 'Fm4', 'Fm5', 'Fm6'};
+
%% Run the linearization
+Ga = -linearize(mdl, io, options);
+Ga.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
+Ga.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6', 'Fm1', 'Fm2', 'Fm3', 'Fm4', 'Fm5', 'Fm6'};
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart);
- stewart = initializeFlexibleStrutDynamics(stewart, 'H', 0.03, 'K', apa.K, 'M', apa.M, 'n_xyz', apa.n_xyz, 'xi', 0.1, 'Gf', -2.65e7, 'step_file', 'mat/APA300ML.STEP');
- stewart = initializeJointDynamics(stewart, 'type_F', 'flexible', 'K_F', flex_joint.K, 'M_F', flex_joint.M, 'n_xyz_F', flex_joint.n_xyz, 'xi_F', 0.1, 'step_file_F', 'mat/flexor_ID16.STEP', 'type_M', 'flexible', 'K_M', flex_joint.K, 'M_M', flex_joint.M, 'n_xyz_M', flex_joint.n_xyz, 'xi_M', 0.1, 'step_file_M', 'mat/flexor_ID16.STEP');
- stewart = initializeCylindricalPlatforms(stewart);
- stewart = initializeCylindricalStruts(stewart, 'type_F', 'none', 'type_M', 'none');
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeInertialSensor(stewart);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart);
+stewart = initializeFlexibleStrutDynamics(stewart, 'H', 0.03, 'K', apa.K, 'M', apa.M, 'n_xyz', apa.n_xyz, 'xi', 0.1, 'Gf', -2.65e7, 'step_file', 'mat/APA300ML.STEP');
+stewart = initializeJointDynamics(stewart, 'type_F', 'flexible', 'K_F', flex_joint.K, 'M_F', flex_joint.M, 'n_xyz_F', flex_joint.n_xyz, 'xi_F', 0.1, 'step_file_F', 'mat/flexor_ID16.STEP', 'type_M', 'flexible', 'K_M', flex_joint.K, 'M_M', flex_joint.M, 'n_xyz_M', flex_joint.n_xyz, 'xi_M', 0.1, 'step_file_M', 'mat/flexor_ID16.STEP');
+stewart = initializeCylindricalPlatforms(stewart);
+stewart = initializeCylindricalStruts(stewart, 'type_F', 'none', 'type_M', 'none');
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeInertialSensor(stewart);
Gf = -linearize(mdl, io, options);
- Gf.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
- Gf.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6', 'Fm1', 'Fm2', 'Fm3', 'Fm4', 'Fm5', 'Fm6'};
+
Gf = -linearize(mdl, io, options);
+Gf.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
+Gf.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6', 'Fm1', 'Fm2', 'Fm3', 'Fm4', 'Fm5', 'Fm6'};
1.8 Save
save('./mat/flexible_stewart_platform.mat', 'G', 'Gj', 'Ga', 'Gf');
+
save('./mat/flexible_stewart_platform.mat', 'G', 'Gj', 'Ga', 'Gf');
1.12 Conclusion
+1.12 Conclusion
2.1 Flexible APA and Flexible Joint
apa = load('./mat/APA300ML.mat', 'int_xyz', 'int_i', 'n_xyz', 'n_i', 'nodes', 'M', 'K');
- flex_joint = load('./mat/flexor_ID16.mat', 'int_xyz', 'int_i', 'n_xyz', 'n_i', 'nodes', 'M', 'K');
+
apa = load('./mat/APA300ML.mat', 'int_xyz', 'int_i', 'n_xyz', 'n_i', 'nodes', 'M', 'K');
+flex_joint = load('./mat/flexor_ID16.mat', 'int_xyz', 'int_i', 'n_xyz', 'n_i', 'nodes', 'M', 'K');
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart);
- stewart = initializeFlexibleStrutDynamics(stewart, 'H', 0.03, 'K', apa.K, 'M', apa.M, 'n_xyz', apa.n_xyz, 'xi', 0.1, 'step_file', 'mat/APA300ML.STEP');
- stewart = initializeJointDynamics(stewart, 'type_F', 'flexible', 'K_F', flex_joint.K, 'M_F', flex_joint.M, 'n_xyz_F', flex_joint.n_xyz, 'xi_F', 0.1, 'step_file_F', 'mat/flexor_ID16.STEP', 'type_M', 'flexible', 'K_M', flex_joint.K, 'M_M', flex_joint.M, 'n_xyz_M', flex_joint.n_xyz, 'xi_M', 0.1, 'step_file_M', 'mat/flexor_ID16.STEP');
- stewart = initializeCylindricalPlatforms(stewart);
- stewart = initializeCylindricalStruts(stewart, 'type_F', 'none', 'type_M', 'none');
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeInertialSensor(stewart);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart);
+stewart = initializeFlexibleStrutDynamics(stewart, 'H', 0.03, 'K', apa.K, 'M', apa.M, 'n_xyz', apa.n_xyz, 'xi', 0.1, 'step_file', 'mat/APA300ML.STEP');
+stewart = initializeJointDynamics(stewart, 'type_F', 'flexible', 'K_F', flex_joint.K, 'M_F', flex_joint.M, 'n_xyz_F', flex_joint.n_xyz, 'xi_F', 0.1, 'step_file_F', 'mat/flexor_ID16.STEP', 'type_M', 'flexible', 'K_M', flex_joint.K, 'M_M', flex_joint.M, 'n_xyz_M', flex_joint.n_xyz, 'xi_M', 0.1, 'step_file_M', 'mat/flexor_ID16.STEP');
+stewart = initializeCylindricalPlatforms(stewart);
+stewart = initializeCylindricalStruts(stewart, 'type_F', 'none', 'type_M', 'none');
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeInertialSensor(stewart);
ground = initializeGround('type', 'none');
- payload = initializePayload('type', 'rigid', 'm', 50);
- controller = initializeController('type', 'open-loop');
+
ground = initializeGround('type', 'none');
+payload = initializePayload('type', 'rigid', 'm', 50);
+controller = initializeController('type', 'open-loop');
disturbances = initializeDisturbances();
- references = initializeReferences(stewart);
+
disturbances = initializeDisturbances();
+references = initializeReferences(stewart);
2.2 Identification
+2.2 Identification
%% Options for Linearized
- options = linearizeOptions;
- options.SampleTime = 0;
+
%% Options for Linearized
+options = linearizeOptions;
+options.SampleTime = 0;
- %% Name of the Simulink File
- mdl = 'stewart_platform_model';
+%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
- io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'dLm'); io_i = io_i + 1; % Relative Displacement Outputs [m]
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
+io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'dLm'); io_i = io_i + 1; % Relative Displacement Outputs [m]
G = -linearize(mdl, io, options);
- G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
- G.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6'};
+
G = -linearize(mdl, io, options);
+G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
+G.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6'};
Kl = -1e5*s/(1 + s/2/pi/2e2)/(1 + s/2/pi/5e2) * eye(6);
+
Kl = -1e5*s/(1 + s/2/pi/2e2)/(1 + s/2/pi/5e2) * eye(6);
isstable(feedback(G(1:6,1:6)*Kl, eye(6), -1))
+
isstable(feedback(G(1:6,1:6)*Kl, eye(6), -1))
2.4 HAC
Kx = tf(zeros(6));
+
Kx = tf(zeros(6));
- controller = initializeController('type', 'ref-track-hac-dvf');
+controller = initializeController('type', 'ref-track-hac-dvf');
%% Name of the Simulink File
- mdl = 'stewart_platform_model';
+
%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Controller'], 1, 'input'); io_i = io_i + 1; % Actuator Force Inputs [N]
- io(io_i) = linio([mdl, '/Relative Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Relative Displacement Outputs [m]
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Controller'], 1, 'input'); io_i = io_i + 1; % Actuator Force Inputs [N]
+io(io_i) = linio([mdl, '/Relative Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Relative Displacement Outputs [m]
- %% Run the linearization
- G = linearize(mdl, io);
- G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
- G.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
+%% Run the linearization
+G = linearize(mdl, io);
+G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
+G.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
Gl = -stewart.kinematics.J*G;
- Gl.OutputName = {'D1', 'D2', 'D3', 'D4', 'D5', 'D6'};
+
Gl = -stewart.kinematics.J*G;
+Gl.OutputName = {'D1', 'D2', 'D3', 'D4', 'D5', 'D6'};
wc = 2*pi*300;
- Kl = diag(1./diag(abs(freqresp(Gl, wc)))) * wc/s * 1/(1 + s/3/wc);
+
wc = 2*pi*300;
+Kl = diag(1./diag(abs(freqresp(Gl, wc)))) * wc/s * 1/(1 + s/3/wc);
3 Flexible Joint Specifications
3.1 Stewart Platform Initialization
+3.1 Stewart Platform Initialization
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart);
- stewart = initializeAmplifiedStrutDynamics(stewart, 'Ke', 1.5e6*ones(6,1), 'Ka', 43e6*ones(6,1), 'K1', 0.4e6*ones(6,1), 'C1', 10*ones(6,1));
- stewart = initializeCylindricalPlatforms(stewart);
- stewart = initializeCylindricalStruts(stewart);
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeInertialSensor(stewart);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart);
+stewart = initializeAmplifiedStrutDynamics(stewart, 'Ke', 1.5e6*ones(6,1), 'Ka', 43e6*ones(6,1), 'K1', 0.4e6*ones(6,1), 'C1', 10*ones(6,1));
+stewart = initializeCylindricalPlatforms(stewart);
+stewart = initializeCylindricalStruts(stewart);
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeInertialSensor(stewart);
- references = initializeReferences(stewart);
+references = initializeReferences(stewart);
ground = initializeGround('type', 'none');
- payload = initializePayload('type', 'rigid', 'm', 50);
- controller = initializeController('type', 'open-loop');
+
ground = initializeGround('type', 'none');
+payload = initializePayload('type', 'rigid', 'm', 50);
+controller = initializeController('type', 'open-loop');
disturbances = initializeDisturbances();
+
disturbances = initializeDisturbances();
open('stewart_platform_model.slx')
+
open('stewart_platform_model.slx')
3.2 Effect of the Bending Stiffness
Kfs = [1, 10, 100, 1000]; % [Nm/rad]
+
Kfs = [1, 10, 100, 1000]; % [Nm/rad]
3.3 Effect of the Torsion Stiffness
Kts = [10, 100, 500, 1000]; % [Nm/rad]
+
Kts = [10, 100, 500, 1000]; % [Nm/rad]
3.4 Effect of the Axial Stiffness
Kas = [1e6, 1e7, 1e8, 5e8, 1e9]; % [N/m]
+
Kas = [1e6, 1e7, 1e8, 5e8, 1e9]; % [N/m]
3.5 Effect of the Radial (Shear) Stiffness
Krs = [1e4, 1e5, 1e6, 1e7]; % [N/m]
+
Krs = [1e4, 1e5, 1e6, 1e7]; % [N/m]
3.6 Comparison of perfect joint and worst specified joint
+3.6 Comparison of perfect joint and worst specified joint
3.7 Conclusion
+3.7 Conclusion
4 Flexible Joint Specifications with the APA300ML
4.1 Stewart Platform Initialization
+4.1 Stewart Platform Initialization
apa = load('./mat/APA300ML.mat', 'int_xyz', 'int_i', 'n_xyz', 'n_i', 'nodes', 'M', 'K');
+
apa = load('./mat/APA300ML.mat', 'int_xyz', 'int_i', 'n_xyz', 'n_i', 'nodes', 'M', 'K');
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart);
- stewart = initializeFlexibleStrutDynamics(stewart, 'H', 0.03, 'K', apa.K, 'M', apa.M, 'n_xyz', apa.n_xyz, 'xi', 0.1, 'step_file', 'mat/APA300ML.STEP');
- stewart = initializeCylindricalPlatforms(stewart);
- stewart = initializeCylindricalStruts(stewart, 'type_F', 'none', 'type_M', 'none');
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeInertialSensor(stewart);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart);
+stewart = initializeFlexibleStrutDynamics(stewart, 'H', 0.03, 'K', apa.K, 'M', apa.M, 'n_xyz', apa.n_xyz, 'xi', 0.1, 'step_file', 'mat/APA300ML.STEP');
+stewart = initializeCylindricalPlatforms(stewart);
+stewart = initializeCylindricalStruts(stewart, 'type_F', 'none', 'type_M', 'none');
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeInertialSensor(stewart);
- references = initializeReferences(stewart);
+references = initializeReferences(stewart);
ground = initializeGround('type', 'none');
- payload = initializePayload('type', 'rigid', 'm', 50);
- controller = initializeController('type', 'open-loop');
+
ground = initializeGround('type', 'none');
+payload = initializePayload('type', 'rigid', 'm', 50);
+controller = initializeController('type', 'open-loop');
disturbances = initializeDisturbances();
+
disturbances = initializeDisturbances();
open('stewart_platform_model.slx')
+
open('stewart_platform_model.slx')
4.2 Comparison of perfect joint and worst specified joint
+4.2 Comparison of perfect joint and worst specified joint
5 Relative Motion Sensors
5.1 Stewart Platform Initialization
+5.1 Stewart Platform Initialization
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart);
apa = load('./mat/APA300ML.mat', 'int_xyz', 'int_i', 'n_xyz', 'n_i', 'nodes', 'M', 'K');
- stewart = initializeAmplifiedStrutDynamics(stewart, 'Ke', 1.5e6*ones(6,1), 'Ka', 40.5e6*ones(6,1), 'K1', 0.4e6*ones(6,1));
- % stewart = initializeFlexibleStrutDynamics(stewart, 'H', 0.03, 'K', apa.K, 'M', apa.M, 'n_xyz', apa.n_xyz, 'xi', 0.1, 'step_file', 'mat/APA300ML.STEP');
+
apa = load('./mat/APA300ML.mat', 'int_xyz', 'int_i', 'n_xyz', 'n_i', 'nodes', 'M', 'K');
+stewart = initializeAmplifiedStrutDynamics(stewart, 'Ke', 1.5e6*ones(6,1), 'Ka', 40.5e6*ones(6,1), 'K1', 0.4e6*ones(6,1));
+% stewart = initializeFlexibleStrutDynamics(stewart, 'H', 0.03, 'K', apa.K, 'M', apa.M, 'n_xyz', apa.n_xyz, 'xi', 0.1, 'step_file', 'mat/APA300ML.STEP');
flex_joint = load('./mat/flexor_025.mat', 'int_xyz', 'int_i', 'n_xyz', 'n_i', 'nodes', 'M', 'K');
- stewart = initializeJointDynamics(stewart, 'type_M', 'spherical_3dof', ...
- 'Kr_M', flex_joint.K(1,1)*ones(6,1), ...
- 'Ka_M', flex_joint.K(3,3)*ones(6,1), ...
- 'Kf_M', flex_joint.K(4,4)*ones(6,1), ...
- 'Kt_M', flex_joint.K(6,6)*ones(6,1), ...
- 'type_F', 'universal_3dof', ...
- 'Kr_F', flex_joint.K(1,1)*ones(6,1), ...
- 'Ka_F', flex_joint.K(3,3)*ones(6,1), ...
- 'Kf_F', flex_joint.K(4,4)*ones(6,1), ...
- 'Kt_F', flex_joint.K(6,6)*ones(6,1));
+
flex_joint = load('./mat/flexor_025.mat', 'int_xyz', 'int_i', 'n_xyz', 'n_i', 'nodes', 'M', 'K');
+stewart = initializeJointDynamics(stewart, 'type_M', 'spherical_3dof', ...
+ 'Kr_M', flex_joint.K(1,1)*ones(6,1), ...
+ 'Ka_M', flex_joint.K(3,3)*ones(6,1), ...
+ 'Kf_M', flex_joint.K(4,4)*ones(6,1), ...
+ 'Kt_M', flex_joint.K(6,6)*ones(6,1), ...
+ 'type_F', 'universal_3dof', ...
+ 'Kr_F', flex_joint.K(1,1)*ones(6,1), ...
+ 'Ka_F', flex_joint.K(3,3)*ones(6,1), ...
+ 'Kf_F', flex_joint.K(4,4)*ones(6,1), ...
+ 'Kt_F', flex_joint.K(6,6)*ones(6,1));
stewart = initializeCylindricalPlatforms(stewart);
+
stewart = initializeCylindricalPlatforms(stewart);
stewart = initializeCylindricalStruts(stewart);
+
stewart = initializeCylindricalStruts(stewart);
stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeInertialSensor(stewart);
+
stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeInertialSensor(stewart);
- references = initializeReferences(stewart);
+references = initializeReferences(stewart);
ground = initializeGround('type', 'none');
- payload = initializePayload('type', 'rigid', 'm', 50);
- controller = initializeController('type', 'open-loop');
+
ground = initializeGround('type', 'none');
+payload = initializePayload('type', 'rigid', 'm', 50);
+controller = initializeController('type', 'open-loop');
disturbances = initializeDisturbances();
+
disturbances = initializeDisturbances();
6.1 Flexible Strut
apa = load('./mat/strut_encoder.mat', 'int_xyz', 'int_i', 'n_xyz', 'n_i', 'nodes', 'M', 'K');
+
apa = load('./mat/strut_encoder.mat', 'int_xyz', 'int_i', 'n_xyz', 'n_i', 'nodes', 'M', 'K');
6.2 Stewart Platform
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', 95e-3, 'MO_B', 220e-3);
- stewart = generateGeneralConfiguration(stewart, 'FH', 22.5e-3, 'FR', 114e-3, 'FTh', [ -11, 11, 120-11, 120+11, 240-11, 240+11]*(pi/180), ...
- 'MH', 22.5e-3, 'MR', 110e-3, 'MTh', [-60+15, 60-15, 60+15, 180-15, 180+15, -60-15]*(pi/180));
- stewart = computeJointsPose(stewart);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', 95e-3, 'MO_B', 220e-3);
+stewart = generateGeneralConfiguration(stewart, 'FH', 22.5e-3, 'FR', 114e-3, 'FTh', [ -11, 11, 120-11, 120+11, 240-11, 240+11]*(pi/180), ...
+ 'MH', 22.5e-3, 'MR', 110e-3, 'MTh', [-60+15, 60-15, 60+15, 180-15, 180+15, -60-15]*(pi/180));
+stewart = computeJointsPose(stewart);
- stewart = initializeFlexibleStrutAndJointDynamics(stewart, 'H', (apa.int_xyz(1,3) - apa.int_xyz(2,3)), ...
- 'K', apa.K, ...
- 'M', apa.M, ...
- 'n_xyz', apa.n_xyz, ...
- 'xi', 0.1, ...
- 'Gf', -2.65e7, ...
- 'step_file', 'mat/APA300ML.STEP');
+stewart = initializeFlexibleStrutAndJointDynamics(stewart, 'H', (apa.int_xyz(1,3) - apa.int_xyz(2,3)), ...
+ 'K', apa.K, ...
+ 'M', apa.M, ...
+ 'n_xyz', apa.n_xyz, ...
+ 'xi', 0.1, ...
+ 'Gf', -2.65e7, ...
+ 'step_file', 'mat/APA300ML.STEP');
- stewart = initializeSolidPlatforms(stewart);
- stewart = initializeCylindricalStruts(stewart, 'type_F', 'none', 'type_M', 'none');
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeInertialSensor(stewart);
+stewart = initializeSolidPlatforms(stewart);
+stewart = initializeCylindricalStruts(stewart, 'type_F', 'none', 'type_M', 'none');
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeInertialSensor(stewart);
disturbances = initializeDisturbances();
- ground = initializeGround('type', 'none');
- payload = initializePayload('type', 'rigid', 'm', 1);
- controller = initializeController('type', 'open-loop');
- references = initializeReferences(stewart);
+
disturbances = initializeDisturbances();
+ground = initializeGround('type', 'none');
+payload = initializePayload('type', 'rigid', 'm', 1);
+controller = initializeController('type', 'open-loop');
+references = initializeReferences(stewart);
%% Options for Linearized
- options = linearizeOptions;
- options.SampleTime = 0;
+
%% Options for Linearized
+options = linearizeOptions;
+options.SampleTime = 0;
- %% Name of the Simulink File
- mdl = 'stewart_platform_model';
+%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
- io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'dLm'); io_i = io_i + 1; % Relative Displacement Outputs [m]
- io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'Lm'); io_i = io_i + 1; % Force Sensors [N]
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
+io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'dLm'); io_i = io_i + 1; % Relative Displacement Outputs [m]
+io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'Lm'); io_i = io_i + 1; % Force Sensors [N]
%% Run the linearization
- G = linearize(mdl, io, options);
- G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
- G.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6', ...
- 'D1', 'D2', 'D3', 'D4', 'D5', 'D6'};
+
%% Run the linearization
+G = linearize(mdl, io, options);
+G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
+G.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6', ...
+ 'D1', 'D2', 'D3', 'D4', 'D5', 'D6'};
1.1 Initialize the Stewart Platform
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart);
- stewart = initializeStrutDynamics(stewart);
- stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p');
- stewart = initializeCylindricalPlatforms(stewart);
- stewart = initializeCylindricalStruts(stewart);
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeInertialSensor(stewart);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart);
+stewart = initializeStrutDynamics(stewart);
+stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p');
+stewart = initializeCylindricalPlatforms(stewart);
+stewart = initializeCylindricalStruts(stewart);
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeInertialSensor(stewart);
ground = initializeGround('type', 'none');
- payload = initializePayload('type', 'none');
- controller = initializeController('type', 'open-loop');
+
ground = initializeGround('type', 'none');
+payload = initializePayload('type', 'none');
+controller = initializeController('type', 'open-loop');
1.2 Identification
%% Options for Linearized
- options = linearizeOptions;
- options.SampleTime = 0;
+
%% Options for Linearized
+options = linearizeOptions;
+options.SampleTime = 0;
- %% Name of the Simulink File
- mdl = 'stewart_platform_model';
+%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
- io(io_i) = linio([mdl, '/Relative Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Position/Orientation of {B} w.r.t. {A}
- io(io_i) = linio([mdl, '/Relative Motion Sensor'], 2, 'openoutput'); io_i = io_i + 1; % Velocity of {B} w.r.t. {A}
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
+io(io_i) = linio([mdl, '/Relative Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Position/Orientation of {B} w.r.t. {A}
+io(io_i) = linio([mdl, '/Relative Motion Sensor'], 2, 'openoutput'); io_i = io_i + 1; % Velocity of {B} w.r.t. {A}
- %% Run the linearization
- G = linearize(mdl, io);
- % G.InputName = {'tau1', 'tau2', 'tau3', 'tau4', 'tau5', 'tau6'};
- % G.OutputName = {'Xdx', 'Xdy', 'Xdz', 'Xrx', 'Xry', 'Xrz', 'Vdx', 'Vdy', 'Vdz', 'Vrx', 'Vry', 'Vrz'};
+%% Run the linearization
+G = linearize(mdl, io);
+% G.InputName = {'tau1', 'tau2', 'tau3', 'tau4', 'tau5', 'tau6'};
+% G.OutputName = {'Xdx', 'Xdy', 'Xdz', 'Xrx', 'Xry', 'Xrz', 'Vdx', 'Vdy', 'Vdz', 'Vrx', 'Vry', 'Vrz'};
G
:
size(G)
+
size(G)
Gm = minreal(G);
+
Gm = minreal(G);
ss2ss
command.
Gt = ss2ss(Gm, Gm.C);
+
Gt = ss2ss(Gm, Gm.C);
At = Gm.C*Gm.A*pinv(Gm.C);
+
At = Gm.C*Gm.A*pinv(Gm.C);
- Bt = Gm.C*Gm.B;
+Bt = Gm.C*Gm.B;
- Ct = eye(12);
- Dt = zeros(12, 6);
+Ct = eye(12);
+Dt = zeros(12, 6);
- Gt = ss(At, Bt, Ct, Dt);
+Gt = ss(At, Bt, Ct, Dt);
1.4 Analysis
[V,D] = eig(Gt.A);
+
[V,D] = eig(Gt.A);
ws = imag(diag(D));
- [ws,I] = sort(ws)
- ws = ws(7:end); I = I(7:end);
+
ws = imag(diag(D));
+[ws,I] = sort(ws)
+ws = ws(7:end); I = I(7:end);
for i = 1:length(ws)
+
for i = 1:length(ws)
i_mode = I(i); % the argument is the i'th mode
+
i_mode = I(i); % the argument is the i'th mode
lambda_i = D(i_mode, i_mode);
- xi_i = V(:,i_mode);
+
lambda_i = D(i_mode, i_mode);
+xi_i = V(:,i_mode);
- a_i = real(lambda_i);
- b_i = imag(lambda_i);
+a_i = real(lambda_i);
+b_i = imag(lambda_i);
t = linspace(0, 10/(imag(lambda_i)/2/pi), 1000);
- U_i = pinv(Gt.B) * real(xi_i * lambda_i * (cos(b_i * t) + 1i*sin(b_i * t)));
+
t = linspace(0, 10/(imag(lambda_i)/2/pi), 1000);
+U_i = pinv(Gt.B) * real(xi_i * lambda_i * (cos(b_i * t) + 1i*sin(b_i * t)));
U = timeseries(U_i, t);
+
U = timeseries(U_i, t);
load('mat/conf_simscape.mat');
- set_param(conf_simscape, 'StopTime', num2str(t(end)));
- sim(mdl);
+
load('mat/conf_simscape.mat');
+set_param(conf_simscape, 'StopTime', num2str(t(end)));
+sim(mdl);
smwritevideo(mdl, sprintf('figs/mode%i', i), ...
- 'PlaybackSpeedRatio', 1/(b_i/2/pi), ...
- 'FrameRate', 30, ...
- 'FrameSize', [800, 400]);
+
smwritevideo(mdl, sprintf('figs/mode%i', i), ...
+ 'PlaybackSpeedRatio', 1/(b_i/2/pi), ...
+ 'FrameRate', 30, ...
+ 'FrameSize', [800, 400]);
end
+
end
2.1 Initialize the Stewart platform
+2.1 Initialize the Stewart platform
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart);
- stewart = initializeStrutDynamics(stewart);
- stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p');
- stewart = initializeCylindricalPlatforms(stewart);
- stewart = initializeCylindricalStruts(stewart);
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeInertialSensor(stewart, 'type', 'accelerometer', 'freq', 5e3);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart);
+stewart = initializeStrutDynamics(stewart);
+stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p');
+stewart = initializeCylindricalPlatforms(stewart);
+stewart = initializeCylindricalStruts(stewart);
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeInertialSensor(stewart, 'type', 'accelerometer', 'freq', 5e3);
ground = initializeGround('type', 'rigid', 'rot_point', stewart.platform_F.FO_A);
- payload = initializePayload('type', 'rigid');
- controller = initializeController('type', 'open-loop');
+
ground = initializeGround('type', 'rigid', 'rot_point', stewart.platform_F.FO_A);
+payload = initializePayload('type', 'rigid');
+controller = initializeController('type', 'open-loop');
2.2 Transmissibility
%% Options for Linearized
- options = linearizeOptions;
- options.SampleTime = 0;
+
%% Options for Linearized
+options = linearizeOptions;
+options.SampleTime = 0;
- %% Name of the Simulink File
- mdl = 'stewart_platform_model';
+%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Disturbances/D_w'], 1, 'openinput'); io_i = io_i + 1; % Base Motion [m, rad]
- io(io_i) = linio([mdl, '/Absolute Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Absolute Motion [m, rad]
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Disturbances/D_w'], 1, 'openinput'); io_i = io_i + 1; % Base Motion [m, rad]
+io(io_i) = linio([mdl, '/Absolute Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Absolute Motion [m, rad]
- %% Run the linearization
- T = linearize(mdl, io, options);
- T.InputName = {'Wdx', 'Wdy', 'Wdz', 'Wrx', 'Wry', 'Wrz'};
- T.OutputName = {'Edx', 'Edy', 'Edz', 'Erx', 'Ery', 'Erz'};
+%% Run the linearization
+T = linearize(mdl, io, options);
+T.InputName = {'Wdx', 'Wdy', 'Wdz', 'Wrx', 'Wry', 'Wrz'};
+T.OutputName = {'Edx', 'Edy', 'Edz', 'Erx', 'Ery', 'Erz'};
freqs = logspace(1, 4, 1000);
+
freqs = logspace(1, 4, 1000);
- figure;
- for ix = 1:6
+figure;
+for ix = 1:6
for iy = 1:6
- subplot(6, 6, (ix-1)*6 + iy);
- hold on;
- plot(freqs, abs(squeeze(freqresp(T(ix, iy), freqs, 'Hz'))), 'k-');
- set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
- ylim([1e-5, 10]);
- xlim([freqs(1), freqs(end)]);
- if ix < 6
- xticklabels({});
- end
- if iy > 1
- yticklabels({});
- end
+ subplot(6, 6, (ix-1)*6 + iy);
+ hold on;
+ plot(freqs, abs(squeeze(freqresp(T(ix, iy), freqs, 'Hz'))), 'k-');
+ set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
+ ylim([1e-5, 10]);
+ xlim([freqs(1), freqs(end)]);
+ if ix < 6
+ xticklabels({});
+ end
+ if iy > 1
+ yticklabels({});
+ end
end
- end
+end
freqs = logspace(1, 4, 1000);
+
freqs = logspace(1, 4, 1000);
- T_norm = zeros(length(freqs), 1);
+T_norm = zeros(length(freqs), 1);
- for i = 1:length(freqs)
+for i = 1:length(freqs)
T_norm(i) = sqrt(trace(freqresp(T, freqs(i), 'Hz')*freqresp(T, freqs(i), 'Hz')'));
- end
+end
Gamma = T_norm/sqrt(6);
+
Gamma = T_norm/sqrt(6);
figure;
- plot(freqs, Gamma)
- set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
+
figure;
+plot(freqs, Gamma)
+set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
3.1 Initialize the Stewart platform
+3.1 Initialize the Stewart platform
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart);
- stewart = initializeStrutDynamics(stewart);
- stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p');
- stewart = initializeCylindricalPlatforms(stewart);
- stewart = initializeCylindricalStruts(stewart);
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeInertialSensor(stewart, 'type', 'accelerometer', 'freq', 5e3);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart);
+stewart = initializeStrutDynamics(stewart);
+stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p');
+stewart = initializeCylindricalPlatforms(stewart);
+stewart = initializeCylindricalStruts(stewart);
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeInertialSensor(stewart, 'type', 'accelerometer', 'freq', 5e3);
ground = initializeGround('type', 'none');
- payload = initializePayload('type', 'rigid');
- controller = initializeController('type', 'open-loop');
+
ground = initializeGround('type', 'none');
+payload = initializePayload('type', 'rigid');
+controller = initializeController('type', 'open-loop');
3.2 Compliance
%% Options for Linearized
- options = linearizeOptions;
- options.SampleTime = 0;
+
%% Options for Linearized
+options = linearizeOptions;
+options.SampleTime = 0;
- %% Name of the Simulink File
- mdl = 'stewart_platform_model';
+%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Disturbances/F_ext'], 1, 'openinput'); io_i = io_i + 1; % Base Motion [m, rad]
- io(io_i) = linio([mdl, '/Absolute Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Absolute Motion [m, rad]
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Disturbances/F_ext'], 1, 'openinput'); io_i = io_i + 1; % Base Motion [m, rad]
+io(io_i) = linio([mdl, '/Absolute Motion Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Absolute Motion [m, rad]
- %% Run the linearization
- C = linearize(mdl, io, options);
- C.InputName = {'Fdx', 'Fdy', 'Fdz', 'Mdx', 'Mdy', 'Mdz'};
- C.OutputName = {'Edx', 'Edy', 'Edz', 'Erx', 'Ery', 'Erz'};
+%% Run the linearization
+C = linearize(mdl, io, options);
+C.InputName = {'Fdx', 'Fdy', 'Fdz', 'Mdx', 'Mdy', 'Mdz'};
+C.OutputName = {'Edx', 'Edy', 'Edz', 'Erx', 'Ery', 'Erz'};
freqs = logspace(1, 4, 1000);
+
freqs = logspace(1, 4, 1000);
- figure;
- for ix = 1:6
+figure;
+for ix = 1:6
for iy = 1:6
- subplot(6, 6, (ix-1)*6 + iy);
- hold on;
- plot(freqs, abs(squeeze(freqresp(C(ix, iy), freqs, 'Hz'))), 'k-');
- set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
- ylim([1e-10, 1e-3]);
- xlim([freqs(1), freqs(end)]);
- if ix < 6
- xticklabels({});
- end
- if iy > 1
- yticklabels({});
- end
+ subplot(6, 6, (ix-1)*6 + iy);
+ hold on;
+ plot(freqs, abs(squeeze(freqresp(C(ix, iy), freqs, 'Hz'))), 'k-');
+ set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
+ ylim([1e-10, 1e-3]);
+ xlim([freqs(1), freqs(end)]);
+ if ix < 6
+ xticklabels({});
+ end
+ if iy > 1
+ yticklabels({});
+ end
end
- end
+end
freqs = logspace(1, 4, 1000);
+
freqs = logspace(1, 4, 1000);
- C_norm = zeros(length(freqs), 1);
+C_norm = zeros(length(freqs), 1);
- for i = 1:length(freqs)
+for i = 1:length(freqs)
C_norm(i) = sqrt(trace(freqresp(C, freqs(i), 'Hz')*freqresp(C, freqs(i), 'Hz')'));
- end
+end
figure;
- plot(freqs, C_norm)
- set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
+
figure;
+plot(freqs, C_norm)
+set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
Function description
-Function description
+ function [T, T_norm, freqs] = computeTransmissibility(args)
- % computeTransmissibility -
- %
- % Syntax: [T, T_norm, freqs] = computeTransmissibility(args)
- %
- % Inputs:
- % - args - Structure with the following fields:
- % - plots [true/false] - Should plot the transmissilibty matrix and its Frobenius norm
- % - freqs [] - Frequency vector to estimate the Frobenius norm
- %
- % Outputs:
- % - T [6x6 ss] - Transmissibility matrix
- % - T_norm [length(freqs)x1] - Frobenius norm of the Transmissibility matrix
- % - freqs [length(freqs)x1] - Frequency vector in [Hz]
+
function [T, T_norm, freqs] = computeTransmissibility(args)
+% computeTransmissibility -
+%
+% Syntax: [T, T_norm, freqs] = computeTransmissibility(args)
+%
+% Inputs:
+% - args - Structure with the following fields:
+% - plots [true/false] - Should plot the transmissilibty matrix and its Frobenius norm
+% - freqs [] - Frequency vector to estimate the Frobenius norm
+%
+% Outputs:
+% - T [6x6 ss] - Transmissibility matrix
+% - T_norm [length(freqs)x1] - Frobenius norm of the Transmissibility matrix
+% - freqs [length(freqs)x1] - Frequency vector in [Hz]
Optional Parameters
-Optional Parameters
+ arguments
- args.plots logical {mustBeNumericOrLogical} = false
- args.freqs double {mustBeNumeric, mustBeNonnegative} = logspace(1,4,1000)
- end
+
arguments
+ args.plots logical {mustBeNumericOrLogical} = false
+ args.freqs double {mustBeNumeric, mustBeNonnegative} = logspace(1,4,1000)
+end
freqs = args.freqs;
+
freqs = args.freqs;
Identification of the Transmissibility Matrix
%% Options for Linearized
- options = linearizeOptions;
- options.SampleTime = 0;
+
%% Options for Linearized
+options = linearizeOptions;
+options.SampleTime = 0;
- %% Name of the Simulink File
- mdl = 'stewart_platform_model';
+%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Disturbances/D_w'], 1, 'openinput'); io_i = io_i + 1; % Base Motion [m, rad]
- io(io_i) = linio([mdl, '/Absolute Motion Sensor'], 1, 'output'); io_i = io_i + 1; % Absolute Motion [m, rad]
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Disturbances/D_w'], 1, 'openinput'); io_i = io_i + 1; % Base Motion [m, rad]
+io(io_i) = linio([mdl, '/Absolute Motion Sensor'], 1, 'output'); io_i = io_i + 1; % Absolute Motion [m, rad]
- %% Run the linearization
- T = linearize(mdl, io, options);
- T.InputName = {'Wdx', 'Wdy', 'Wdz', 'Wrx', 'Wry', 'Wrz'};
- T.OutputName = {'Edx', 'Edy', 'Edz', 'Erx', 'Ery', 'Erz'};
+%% Run the linearization
+T = linearize(mdl, io, options);
+T.InputName = {'Wdx', 'Wdy', 'Wdz', 'Wrx', 'Wry', 'Wrz'};
+T.OutputName = {'Edx', 'Edy', 'Edz', 'Erx', 'Ery', 'Erz'};
p_handle = zeros(6*6,1);
+
p_handle = zeros(6*6,1);
- if args.plots
+if args.plots
fig = figure;
for ix = 1:6
- for iy = 1:6
- p_handle((ix-1)*6 + iy) = subplot(6, 6, (ix-1)*6 + iy);
- hold on;
- plot(freqs, abs(squeeze(freqresp(T(ix, iy), freqs, 'Hz'))), 'k-');
- set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
- if ix < 6
- xticklabels({});
+ for iy = 1:6
+ p_handle((ix-1)*6 + iy) = subplot(6, 6, (ix-1)*6 + iy);
+ hold on;
+ plot(freqs, abs(squeeze(freqresp(T(ix, iy), freqs, 'Hz'))), 'k-');
+ set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
+ if ix < 6
+ xticklabels({});
+ end
+ if iy > 1
+ yticklabels({});
+ end
end
- if iy > 1
- yticklabels({});
- end
- end
end
linkaxes(p_handle, 'xy')
@@ -733,37 +733,37 @@ If wanted, the 6x6 transmissibility matrix is plotted.
han.YLabel.Visible = 'on';
xlabel(han, 'Frequency [Hz]');
ylabel(han, 'Transmissibility [m/m]');
- end
+end
Computation of the Frobenius norm
-Computation of the Frobenius norm
+ T_norm = zeros(length(freqs), 1);
+
T_norm = zeros(length(freqs), 1);
- for i = 1:length(freqs)
+for i = 1:length(freqs)
T_norm(i) = sqrt(trace(freqresp(T, freqs(i), 'Hz')*freqresp(T, freqs(i), 'Hz')'));
- end
+end
T_norm = T_norm/sqrt(6);
+
T_norm = T_norm/sqrt(6);
if args.plots
+
if args.plots
figure;
plot(freqs, T_norm)
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
xlabel('Frequency [Hz]');
ylabel('Transmissibility - Frobenius Norm');
- end
+end
Function description
-Function description
+ function [C, C_norm, freqs] = computeCompliance(args)
- % computeCompliance -
- %
- % Syntax: [C, C_norm, freqs] = computeCompliance(args)
- %
- % Inputs:
- % - args - Structure with the following fields:
- % - plots [true/false] - Should plot the transmissilibty matrix and its Frobenius norm
- % - freqs [] - Frequency vector to estimate the Frobenius norm
- %
- % Outputs:
- % - C [6x6 ss] - Compliance matrix
- % - C_norm [length(freqs)x1] - Frobenius norm of the Compliance matrix
- % - freqs [length(freqs)x1] - Frequency vector in [Hz]
+
function [C, C_norm, freqs] = computeCompliance(args)
+% computeCompliance -
+%
+% Syntax: [C, C_norm, freqs] = computeCompliance(args)
+%
+% Inputs:
+% - args - Structure with the following fields:
+% - plots [true/false] - Should plot the transmissilibty matrix and its Frobenius norm
+% - freqs [] - Frequency vector to estimate the Frobenius norm
+%
+% Outputs:
+% - C [6x6 ss] - Compliance matrix
+% - C_norm [length(freqs)x1] - Frobenius norm of the Compliance matrix
+% - freqs [length(freqs)x1] - Frequency vector in [Hz]
Optional Parameters
-Optional Parameters
+ arguments
- args.plots logical {mustBeNumericOrLogical} = false
- args.freqs double {mustBeNumeric, mustBeNonnegative} = logspace(1,4,1000)
- end
+
arguments
+ args.plots logical {mustBeNumericOrLogical} = false
+ args.freqs double {mustBeNumeric, mustBeNonnegative} = logspace(1,4,1000)
+end
freqs = args.freqs;
+
freqs = args.freqs;
Identification of the Compliance Matrix
%% Options for Linearized
- options = linearizeOptions;
- options.SampleTime = 0;
+
%% Options for Linearized
+options = linearizeOptions;
+options.SampleTime = 0;
- %% Name of the Simulink File
- mdl = 'stewart_platform_model';
+%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Disturbances/F_ext'], 1, 'openinput'); io_i = io_i + 1; % External forces [N, N*m]
- io(io_i) = linio([mdl, '/Absolute Motion Sensor'], 1, 'output'); io_i = io_i + 1; % Absolute Motion [m, rad]
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Disturbances/F_ext'], 1, 'openinput'); io_i = io_i + 1; % External forces [N, N*m]
+io(io_i) = linio([mdl, '/Absolute Motion Sensor'], 1, 'output'); io_i = io_i + 1; % Absolute Motion [m, rad]
- %% Run the linearization
- C = linearize(mdl, io, options);
- C.InputName = {'Fdx', 'Fdy', 'Fdz', 'Mdx', 'Mdy', 'Mdz'};
- C.OutputName = {'Edx', 'Edy', 'Edz', 'Erx', 'Ery', 'Erz'};
+%% Run the linearization
+C = linearize(mdl, io, options);
+C.InputName = {'Fdx', 'Fdy', 'Fdz', 'Mdx', 'Mdy', 'Mdz'};
+C.OutputName = {'Edx', 'Edy', 'Edz', 'Erx', 'Ery', 'Erz'};
p_handle = zeros(6*6,1);
+
p_handle = zeros(6*6,1);
- if args.plots
+if args.plots
fig = figure;
for ix = 1:6
- for iy = 1:6
- p_handle((ix-1)*6 + iy) = subplot(6, 6, (ix-1)*6 + iy);
- hold on;
- plot(freqs, abs(squeeze(freqresp(C(ix, iy), freqs, 'Hz'))), 'k-');
- set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
- if ix < 6
- xticklabels({});
+ for iy = 1:6
+ p_handle((ix-1)*6 + iy) = subplot(6, 6, (ix-1)*6 + iy);
+ hold on;
+ plot(freqs, abs(squeeze(freqresp(C(ix, iy), freqs, 'Hz'))), 'k-');
+ set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
+ if ix < 6
+ xticklabels({});
+ end
+ if iy > 1
+ yticklabels({});
+ end
end
- if iy > 1
- yticklabels({});
- end
- end
end
linkaxes(p_handle, 'xy')
@@ -873,34 +873,34 @@ If wanted, the 6x6 transmissibility matrix is plotted.
han.YLabel.Visible = 'on';
xlabel(han, 'Frequency [Hz]');
ylabel(han, 'Compliance [m/N, rad/(N*m)]');
- end
+end
Computation of the Frobenius norm
-Computation of the Frobenius norm
+ freqs = args.freqs;
+
freqs = args.freqs;
- C_norm = zeros(length(freqs), 1);
+C_norm = zeros(length(freqs), 1);
- for i = 1:length(freqs)
+for i = 1:length(freqs)
C_norm(i) = sqrt(trace(freqresp(C, freqs(i), 'Hz')*freqresp(C, freqs(i), 'Hz')'));
- end
+end
if args.plots
+
if args.plots
figure;
plot(freqs, C_norm)
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
xlabel('Frequency [Hz]');
ylabel('Compliance - Frobenius Norm');
- end
+end
computeJacobian
: Compute the Jacobian Matrix
-
stewart
structure elementsstewart
structure elementsinverseKinematics
: Compute Inverse Kinematics
forwardKinematicsApprox
: Compute the Approximate Forward Kinematics
forwardKinematicsApprox
(described
-4.1 Stewart architecture definition
+4.1 Stewart architecture definition
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeCylindricalPlatforms(stewart);
- stewart = initializeCylindricalStruts(stewart);
- stewart = initializeStrutDynamics(stewart);
- stewart = initializeJointDynamics(stewart);
- stewart = computeJacobian(stewart);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeCylindricalPlatforms(stewart);
+stewart = initializeCylindricalStruts(stewart);
+stewart = initializeStrutDynamics(stewart);
+stewart = initializeJointDynamics(stewart);
+stewart = computeJacobian(stewart);
Xrs = logspace(-6, -1, 100); % Wanted X translation of the mobile platform [m]
+
Xrs = logspace(-6, -1, 100); % Wanted X translation of the mobile platform [m]
- Ls_approx = zeros(6, length(Xrs));
- Ls_exact = zeros(6, length(Xrs));
+Ls_approx = zeros(6, length(Xrs));
+Ls_exact = zeros(6, length(Xrs));
- for i = 1:length(Xrs)
+for i = 1:length(Xrs)
Xr = Xrs(i);
L_approx(:, i) = stewart.kinematics.J*[Xr; 0; 0; 0; 0; 0;];
[~, L_exact(:, i)] = inverseKinematics(stewart, 'AP', [Xr; 0; 0]);
- end
+end
4.3 Conclusion
5.1 Stewart architecture definition
+5.1 Stewart architecture definition
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeCylindricalPlatforms(stewart);
- stewart = initializeCylindricalStruts(stewart);
- stewart = initializeStrutDynamics(stewart);
- stewart = initializeJointDynamics(stewart);
- stewart = computeJacobian(stewart);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeCylindricalPlatforms(stewart);
+stewart = initializeCylindricalStruts(stewart);
+stewart = initializeStrutDynamics(stewart);
+stewart = initializeJointDynamics(stewart);
+stewart = computeJacobian(stewart);
Tx_max = 50e-6; % Translation [m]
- Ty_max = 50e-6; % Translation [m]
- Tz_max = 50e-6; % Translation [m]
- Rx_max = 30e-6; % Rotation [rad]
- Ry_max = 30e-6; % Rotation [rad]
- Rz_max = 0; % Rotation [rad]
+
Tx_max = 50e-6; % Translation [m]
+Ty_max = 50e-6; % Translation [m]
+Tz_max = 50e-6; % Translation [m]
+Rx_max = 30e-6; % Rotation [rad]
+Ry_max = 30e-6; % Rotation [rad]
+Rz_max = 0; % Rotation [rad]
LTx = stewart.kinematics.J*[Tx_max 0 0 0 0 0]';
- LTy = stewart.kinematics.J*[0 Ty_max 0 0 0 0]';
- LTz = stewart.kinematics.J*[0 0 Tz_max 0 0 0]';
- LRx = stewart.kinematics.J*[0 0 0 Rx_max 0 0]';
- LRy = stewart.kinematics.J*[0 0 0 0 Ry_max 0]';
- LRz = stewart.kinematics.J*[0 0 0 0 0 Rz_max]';
+
LTx = stewart.kinematics.J*[Tx_max 0 0 0 0 0]';
+LTy = stewart.kinematics.J*[0 Ty_max 0 0 0 0]';
+LTz = stewart.kinematics.J*[0 0 Tz_max 0 0 0]';
+LRx = stewart.kinematics.J*[0 0 0 Rx_max 0 0]';
+LRy = stewart.kinematics.J*[0 0 0 0 Ry_max 0]';
+LRz = stewart.kinematics.J*[0 0 0 0 0 Rz_max]';
Ps = [2*(dec2bin(0:5^2-1,5)-'0')-1, zeros(5^2, 1)].*[Tx_max Ty_max Tz_max Rx_max Ry_max Rz_max];
+
Ps = [2*(dec2bin(0:5^2-1,5)-'0')-1, zeros(5^2, 1)].*[Tx_max Ty_max Tz_max Rx_max Ry_max Rz_max];
L_min = 0;
- L_max = 0;
+
L_min = 0;
+L_max = 0;
- for i = 1:size(Ps,1)
+for i = 1:size(Ps,1)
Rx = [1 0 0;
0 cos(Ps(i, 4)) -sin(Ps(i, 4));
0 sin(Ps(i, 4)) cos(Ps(i, 4))];
Ry = [ cos(Ps(i, 5)) 0 sin(Ps(i, 5));
- 0 1 0;
- -sin(Ps(i, 5)) 0 cos(Ps(i, 5))];
+ 0 1 0;
+ -sin(Ps(i, 5)) 0 cos(Ps(i, 5))];
Rz = [cos(Ps(i, 6)) -sin(Ps(i, 6)) 0;
sin(Ps(i, 6)) cos(Ps(i, 6)) 0;
@@ -934,12 +934,12 @@ For all possible combination, we compute the required actuator stroke using the
[~, Ls] = inverseKinematics(stewart, 'AP', Ps(i, 1:3)', 'ARB', ARB);
if min(Ls) < L_min
- L_min = min(Ls)
+ L_min = min(Ls)
end
if max(Ls) > L_max
- L_max = max(Ls)
+ L_max = max(Ls)
end
- end
+end
6.1 Stewart architecture definition
+6.1 Stewart architecture definition
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeCylindricalPlatforms(stewart);
- stewart = initializeCylindricalStruts(stewart);
- stewart = initializeStrutDynamics(stewart);
- stewart = initializeJointDynamics(stewart);
- stewart = computeJacobian(stewart);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeCylindricalPlatforms(stewart);
+stewart = initializeCylindricalStruts(stewart);
+stewart = initializeStrutDynamics(stewart);
+stewart = initializeJointDynamics(stewart);
+stewart = computeJacobian(stewart);
L_min = -50e-6; % [m]
- L_max = 50e-6; % [m]
+
L_min = -50e-6; % [m]
+L_max = 50e-6; % [m]
L_min
and L_max
.
thetas = linspace(0, pi, 50);
- phis = linspace(0, 2*pi, 50);
- rs = zeros(length(thetas), length(phis));
+
thetas = linspace(0, pi, 50);
+phis = linspace(0, 2*pi, 50);
+rs = zeros(length(thetas), length(phis));
- for i = 1:length(thetas)
+for i = 1:length(thetas)
for j = 1:length(phis)
- Tx = sin(thetas(i))*cos(phis(j));
- Ty = sin(thetas(i))*sin(phis(j));
- Tz = cos(thetas(i));
+ Tx = sin(thetas(i))*cos(phis(j));
+ Ty = sin(thetas(i))*sin(phis(j));
+ Tz = cos(thetas(i));
- dL = stewart.kinematics.J*[Tx; Ty; Tz; 0; 0; 0;]; % dL required for 1m displacement in theta/phi direction
+ dL = stewart.kinematics.J*[Tx; Ty; Tz; 0; 0; 0;]; % dL required for 1m displacement in theta/phi direction
- rs(i, j) = max([dL(dL<0)*L_min; dL(dL>0)*L_max]);
+ rs(i, j) = max([dL(dL<0)*L_min; dL(dL>0)*L_max]);
end
- end
+end
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 150e-3);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart, 'AP', [0; 0; 0]);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 150e-3);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart, 'AP', [0; 0; 0]);
- As_init = stewart.geometry.As;
+As_init = stewart.geometry.As;
Tx_max = 60e-6; % Translation [m]
- Ty_max = 60e-6; % Translation [m]
- Tz_max = 60e-6; % Translation [m]
- Rx_max = 30e-6; % Rotation [rad]
- Ry_max = 30e-6; % Rotation [rad]
- Rz_max = 0; % Rotation [rad]
+
Tx_max = 60e-6; % Translation [m]
+Ty_max = 60e-6; % Translation [m]
+Tz_max = 60e-6; % Translation [m]
+Rx_max = 30e-6; % Rotation [rad]
+Ry_max = 30e-6; % Rotation [rad]
+Rz_max = 0; % Rotation [rad]
Ps = [2*(dec2bin(0:5^2-1,5)-'0')-1, zeros(5^2, 1)].*[Tx_max Ty_max Tz_max Rx_max Ry_max Rz_max];
+
Ps = [2*(dec2bin(0:5^2-1,5)-'0')-1, zeros(5^2, 1)].*[Tx_max Ty_max Tz_max Rx_max Ry_max Rz_max];
flex_ang = zeros(size(Ps, 1), 6);
- Rxs = zeros(size(Ps, 1), 6)
- Rys = zeros(size(Ps, 1), 6)
- Rzs = zeros(size(Ps, 1), 6)
+
flex_ang = zeros(size(Ps, 1), 6);
+Rxs = zeros(size(Ps, 1), 6)
+Rys = zeros(size(Ps, 1), 6)
+Rzs = zeros(size(Ps, 1), 6)
- for Ps_i = 1:size(Ps, 1)
- Rx = [1 0 0;
- 0 cos(Ps(Ps_i, 4)) -sin(Ps(Ps_i, 4));
- 0 sin(Ps(Ps_i, 4)) cos(Ps(Ps_i, 4))];
+for Ps_i = 1:size(Ps, 1)
+ Rx = [1 0 0;
+ 0 cos(Ps(Ps_i, 4)) -sin(Ps(Ps_i, 4));
+ 0 sin(Ps(Ps_i, 4)) cos(Ps(Ps_i, 4))];
- Ry = [ cos(Ps(Ps_i, 5)) 0 sin(Ps(Ps_i, 5));
- 0 1 0;
- -sin(Ps(Ps_i, 5)) 0 cos(Ps(Ps_i, 5))];
+ Ry = [ cos(Ps(Ps_i, 5)) 0 sin(Ps(Ps_i, 5));
+ 0 1 0;
+ -sin(Ps(Ps_i, 5)) 0 cos(Ps(Ps_i, 5))];
- Rz = [cos(Ps(Ps_i, 6)) -sin(Ps(Ps_i, 6)) 0;
- sin(Ps(Ps_i, 6)) cos(Ps(Ps_i, 6)) 0;
- 0 0 1];
+ Rz = [cos(Ps(Ps_i, 6)) -sin(Ps(Ps_i, 6)) 0;
+ sin(Ps(Ps_i, 6)) cos(Ps(Ps_i, 6)) 0;
+ 0 0 1];
- ARB = Rz*Ry*Rx;
+ ARB = Rz*Ry*Rx;
- stewart = computeJointsPose(stewart, 'AP', Ps(Ps_i, 1:3)', 'ARB', ARB);
+ stewart = computeJointsPose(stewart, 'AP', Ps(Ps_i, 1:3)', 'ARB', ARB);
- flex_ang(Ps_i, :) = acos(sum(As_init.*stewart.geometry.As));
-
- for l_i = 1:6
- MRf = stewart.platform_M.MRb(:,:,l_i)*(ARB')*(stewart.platform_F.FRa(:,:,l_i)');
-
- Rys(Ps_i, l_i) = atan2(MRf(1,3), sqrt(MRf(1,1)^2 + MRf(2,2)^2));
- Rxs(Ps_i, l_i) = atan2(-MRf(2,3)/cos(Rys(Ps_i, l_i)), MRf(3,3)/cos(Rys(Ps_i, l_i)));
- Rzs(Ps_i, l_i) = atan2(-MRf(1,2)/cos(Rys(Ps_i, l_i)), MRf(1,1)/cos(Rys(Ps_i, l_i)));
- end
- end
+ flex_ang(Ps_i, :) = acos(sum(As_init.*stewart.geometry.As));
+
+ for l_i = 1:6
+ MRf = stewart.platform_M.MRb(:,:,l_i)*(ARB')*(stewart.platform_F.FRa(:,:,l_i)');
+
+ Rys(Ps_i, l_i) = atan2(MRf(1,3), sqrt(MRf(1,1)^2 + MRf(2,2)^2));
+ Rxs(Ps_i, l_i) = atan2(-MRf(2,3)/cos(Rys(Ps_i, l_i)), MRf(3,3)/cos(Rys(Ps_i, l_i)));
+ Rzs(Ps_i, l_i) = atan2(-MRf(1,2)/cos(Rys(Ps_i, l_i)), MRf(1,1)/cos(Rys(Ps_i, l_i)));
+ end
+end
1e3*max(max(abs(flex_ang)))
+
1e3*max(max(abs(flex_ang)))
1e3*max(max(sqrt(Rxs.^2 + Rys.^2)))
+
1e3*max(max(sqrt(Rxs.^2 + Rys.^2)))
1e3*max(max(Rzs))
+
1e3*max(max(Rzs))
7.2.1 Model Init
open('stewart_platform_model.slx')
+
open('stewart_platform_model.slx')
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart);
- stewart = initializeStrutDynamics(stewart);
- stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p');
- stewart = initializeCylindricalPlatforms(stewart);
- stewart = initializeCylindricalStruts(stewart);
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeInertialSensor(stewart, 'type', 'accelerometer', 'freq', 5e3);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart);
+stewart = initializeStrutDynamics(stewart);
+stewart = initializeJointDynamics(stewart, 'type_F', 'universal_p', 'type_M', 'spherical_p');
+stewart = initializeCylindricalPlatforms(stewart);
+stewart = initializeCylindricalStruts(stewart);
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeInertialSensor(stewart, 'type', 'accelerometer', 'freq', 5e3);
ground = initializeGround('type', 'rigid');
- payload = initializePayload('type', 'none');
- controller = initializeController('type', 'open-loop');
- disturbances = initializeDisturbances();
- references = initializeReferences(stewart);
+
ground = initializeGround('type', 'rigid');
+payload = initializePayload('type', 'none');
+controller = initializeController('type', 'open-loop');
+disturbances = initializeDisturbances();
+references = initializeReferences(stewart);
7.2.2 Controller design to be close to the wanted displacement
%% Name of the Simulink File
- mdl = 'stewart_platform_model';
+
%% Name of the Simulink File
+mdl = 'stewart_platform_model';
- %% Input/Output definition
- clear io; io_i = 1;
- io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
- io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'dLm'); io_i = io_i + 1; % Relative Displacement Outputs [m]
+%% Input/Output definition
+clear io; io_i = 1;
+io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N]
+io(io_i) = linio([mdl, '/Stewart Platform'], 1, 'openoutput', [], 'dLm'); io_i = io_i + 1; % Relative Displacement Outputs [m]
- %% Run the linearization
- G = linearize(mdl, io);
- G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
- G.OutputName = {'L1', 'L2', 'L3', 'L4', 'L5', 'L6'};
+%% Run the linearization
+G = linearize(mdl, io);
+G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
+G.OutputName = {'L1', 'L2', 'L3', 'L4', 'L5', 'L6'};
wc = 2*pi*30;
- Kl = diag(1./diag(abs(freqresp(G, wc)))) * wc/s * 1/(1 + s/3/wc);
+
wc = 2*pi*30;
+Kl = diag(1./diag(abs(freqresp(G, wc)))) * wc/s * 1/(1 + s/3/wc);
controller = initializeController('type', 'ref-track-L');
+
controller = initializeController('type', 'ref-track-L');
7.2.3 Simulations
Tx_max = 60e-6; % Translation [m]
- Ty_max = 60e-6; % Translation [m]
- Tz_max = 60e-6; % Translation [m]
- Rx_max = 30e-6; % Rotation [rad]
- Ry_max = 30e-6; % Rotation [rad]
- Rz_max = 0; % Rotation [rad]
+
Tx_max = 60e-6; % Translation [m]
+Ty_max = 60e-6; % Translation [m]
+Tz_max = 60e-6; % Translation [m]
+Rx_max = 30e-6; % Rotation [rad]
+Ry_max = 30e-6; % Rotation [rad]
+Rz_max = 0; % Rotation [rad]
Ps = [2*(dec2bin(0:5^2-1,5)-'0')-1, zeros(5^2, 1)].*[Tx_max Ty_max Tz_max Rx_max Ry_max Rz_max];
+
Ps = [2*(dec2bin(0:5^2-1,5)-'0')-1, zeros(5^2, 1)].*[Tx_max Ty_max Tz_max Rx_max Ry_max Rz_max];
cl_perf = zeros(size(Ps, 1), 1); % Closed loop performance [percentage]
- Rs = zeros(size(Ps, 1), 5); % Max Flexor angles for the 6 legs [mrad]
+
cl_perf = zeros(size(Ps, 1), 1); % Closed loop performance [percentage]
+Rs = zeros(size(Ps, 1), 5); % Max Flexor angles for the 6 legs [mrad]
- for Ps_i = 1:size(Ps, 1)
- fprintf('Experiment %i over %i', Ps_i, size(Ps, 1));
-
- references = initializeReferences(stewart, 't', 0, 'r', Ps(Ps_i, :)');
- set_param('stewart_platform_model','StopTime','0.1');
- sim('stewart_platform_model');
+for Ps_i = 1:size(Ps, 1)
+ fprintf('Experiment %i over %i', Ps_i, size(Ps, 1));
- cl_perf(Ps_i) = 100*max(abs((simout.y.dLm.Data(end, :) - references.rL.Data(:,1,1)')./simout.y.dLm.Data(end, :)));
- Rs(Ps_i, :) = [max(abs(1e3*simout.y.Rf.Data(end, 1:2:end))), max(abs(1e3*simout.y.Rf.Data(end, 2:2:end))), max(abs(1e3*simout.y.Rm.Data(end, 1:3:end))), max(abs(1e3*simout.y.Rm.Data(end, 2:3:end))), max(abs(1e3*simout.y.Rm.Data(end, 3:3:end)))]';
- end
+ references = initializeReferences(stewart, 't', 0, 'r', Ps(Ps_i, :)');
+ set_param('stewart_platform_model','StopTime','0.1');
+ sim('stewart_platform_model');
+
+ cl_perf(Ps_i) = 100*max(abs((simout.y.dLm.Data(end, :) - references.rL.Data(:,1,1)')./simout.y.dLm.Data(end, :)));
+ Rs(Ps_i, :) = [max(abs(1e3*simout.y.Rf.Data(end, 1:2:end))), max(abs(1e3*simout.y.Rf.Data(end, 2:2:end))), max(abs(1e3*simout.y.Rm.Data(end, 1:3:end))), max(abs(1e3*simout.y.Rm.Data(end, 2:3:end))), max(abs(1e3*simout.y.Rm.Data(end, 3:3:end)))]';
+end
max(cl_perf)
+
max(cl_perf)
Function description
-Function description
+ 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
+
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
Check the
-stewart
structure elementsCheck the
+stewart
structure elements assert(isfield(stewart.geometry, 'As'), 'stewart.geometry should have attribute As')
- As = stewart.geometry.As;
+
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.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;
+assert(isfield(stewart.actuators, 'K'), 'stewart.actuators should have attribute K')
+Ki = stewart.actuators.K;
Compute Jacobian Matrix
J = [As' , cross(Ab, As)'];
+
J = [As' , cross(Ab, As)'];
Compute Stiffness Matrix
K = J'*diag(Ki)*J;
+
K = J'*diag(Ki)*J;
Compute Compliance Matrix
C = inv(K);
+
C = inv(K);
Populate the
stewart
structure stewart.kinematics.J = J;
- stewart.kinematics.K = K;
- stewart.kinematics.C = C;
+
stewart.kinematics.J = J;
+stewart.kinematics.K = K;
+stewart.kinematics.C = C;
Function description
-Function description
+ 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}
+
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}
Optional Parameters
-Optional Parameters
+ arguments
- stewart
- args.AP (3,1) double {mustBeNumeric} = zeros(3,1)
- args.ARB (3,3) double {mustBeNumeric} = eye(3)
- end
+
arguments
+ stewart
+ args.AP (3,1) double {mustBeNumeric} = zeros(3,1)
+ args.ARB (3,3) double {mustBeNumeric} = eye(3)
+end
Check the
-stewart
structure elementsCheck the
+stewart
structure elements assert(isfield(stewart.geometry, 'Aa'), 'stewart.geometry should have attribute Aa')
- Aa = stewart.geometry.Aa;
+
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, '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;
+assert(isfield(stewart.geometry, 'l'), 'stewart.geometry should have attribute l')
+l = stewart.geometry.l;
Compute
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));
+
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;
+
dLi = Li-l;
Function description
-Function description
+ 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
- % the Jacobian Matrix
- %
- % Syntax: [P, R] = forwardKinematicsApprox(stewart, args)
- %
- % Inputs:
- % - stewart - A structure with the following fields
- % - kinematics.J [6x6] - The Jacobian Matrix
- % - args - Can have the following fields:
- % - dL [6x1] - Displacement of each strut [m]
- %
- % Outputs:
- % - P [3x1] - The estimated position of {B} with respect to {A}
- % - R [3x3] - The estimated rotation matrix that gives the orientation of {B} with respect to {A}
+
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
+% the Jacobian Matrix
+%
+% Syntax: [P, R] = forwardKinematicsApprox(stewart, args)
+%
+% Inputs:
+% - stewart - A structure with the following fields
+% - kinematics.J [6x6] - The Jacobian Matrix
+% - args - Can have the following fields:
+% - dL [6x1] - Displacement of each strut [m]
+%
+% Outputs:
+% - P [3x1] - The estimated position of {B} with respect to {A}
+% - R [3x3] - The estimated rotation matrix that gives the orientation of {B} with respect to {A}
Optional Parameters
-Optional Parameters
+ arguments
- stewart
- args.dL (6,1) double {mustBeNumeric} = zeros(6,1)
- end
+
arguments
+ stewart
+ args.dL (6,1) double {mustBeNumeric} = zeros(6,1)
+end
Check the
-stewart
structure elementsCheck the
+stewart
structure elements assert(isfield(stewart.kinematics, 'J'), 'stewart.kinematics should have attribute J')
- J = stewart.kinematics.J;
+
assert(isfield(stewart.kinematics, 'J'), 'stewart.kinematics should have attribute J')
+J = stewart.kinematics.J;
X = J\args.dL;
+
X = J\args.dL;
P = X(1:3);
+
P = X(1:3);
theta = norm(X(4:6));
- s = X(4:6)/theta;
+
theta = norm(X(4:6));
+s = X(4:6)/theta;
R = [s(1)^2*(1-cos(theta)) + cos(theta) , s(1)*s(2)*(1-cos(theta)) - s(3)*sin(theta), s(1)*s(3)*(1-cos(theta)) + s(2)*sin(theta);
- s(2)*s(1)*(1-cos(theta)) + s(3)*sin(theta), s(2)^2*(1-cos(theta)) + cos(theta), s(2)*s(3)*(1-cos(theta)) - s(1)*sin(theta);
- s(3)*s(1)*(1-cos(theta)) - s(2)*sin(theta), s(3)*s(2)*(1-cos(theta)) + s(1)*sin(theta), s(3)^2*(1-cos(theta)) + cos(theta)];
+
R = [s(1)^2*(1-cos(theta)) + cos(theta) , s(1)*s(2)*(1-cos(theta)) - s(3)*sin(theta), s(1)*s(3)*(1-cos(theta)) + s(2)*sin(theta);
+ s(2)*s(1)*(1-cos(theta)) + s(3)*sin(theta), s(2)^2*(1-cos(theta)) + cos(theta), s(2)*s(3)*(1-cos(theta)) - s(1)*sin(theta);
+ s(3)*s(1)*(1-cos(theta)) - s(2)*sin(theta), s(3)*s(2)*(1-cos(theta)) + s(1)*sin(theta), s(3)^2*(1-cos(theta)) + cos(theta)];
1.1 Identification of the Dynamics
apa = load('./mat/APA300ML.mat', 'int_xyz', 'int_i', 'n_xyz', 'n_i', 'nodes', 'M', 'K');
- flex_joint = load('./mat/flexor_ID16.mat', 'int_xyz', 'int_i', 'n_xyz', 'n_i', 'nodes', 'M', 'K');
+
apa = load('./mat/APA300ML.mat', 'int_xyz', 'int_i', 'n_xyz', 'n_i', 'nodes', 'M', 'K');
+flex_joint = load('./mat/flexor_ID16.mat', 'int_xyz', 'int_i', 'n_xyz', 'n_i', 'nodes', 'M', 'K');
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 175e-3);
- stewart = generateGeneralConfiguration(stewart, 'FH', 20e-3, 'MH', 20e-3, 'FR', 228e-3/2, 'MR', 220e-3/2, 'FTh', [-9, 9, 120-9, 120+9, 240-9, 240+9]*(pi/180), 'MTh', [-60+15, 60-15, 60+15, 180-15, 180+15, -60-15]*(pi/180));
- stewart = computeJointsPose(stewart);
- stewart = initializeFlexibleStrutDynamics(stewart, 'H', 0.03, 'K', apa.K, 'M', apa.M, 'n_xyz', apa.n_xyz, 'xi', 0.1, 'step_file', 'mat/APA300ML.STEP');
- stewart = initializeJointDynamics(stewart, 'type_F', 'flexible', 'K_F', flex_joint.K, 'M_F', flex_joint.M, 'n_xyz_F', flex_joint.n_xyz, 'xi_F', 0.1, 'step_file_F', 'mat/flexor_ID16.STEP', 'type_M', 'flexible', 'K_M', flex_joint.K, 'M_M', flex_joint.M, 'n_xyz_M', flex_joint.n_xyz, 'xi_M', 0.1, 'step_file_M', 'mat/flexor_ID16.STEP');
- stewart = initializeCylindricalPlatforms(stewart, 'Fpr', 150e-3, 'Mpr', 125e-3);
- stewart = initializeCylindricalStruts(stewart, 'type_F', 'none', 'type_M', 'none');
- stewart = computeJacobian(stewart);
- stewart = initializeStewartPose(stewart);
- stewart = initializeInertialSensor(stewart);
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 175e-3);
+stewart = generateGeneralConfiguration(stewart, 'FH', 20e-3, 'MH', 20e-3, 'FR', 228e-3/2, 'MR', 220e-3/2, 'FTh', [-9, 9, 120-9, 120+9, 240-9, 240+9]*(pi/180), 'MTh', [-60+15, 60-15, 60+15, 180-15, 180+15, -60-15]*(pi/180));
+stewart = computeJointsPose(stewart);
+stewart = initializeFlexibleStrutDynamics(stewart, 'H', 0.03, 'K', apa.K, 'M', apa.M, 'n_xyz', apa.n_xyz, 'xi', 0.1, 'step_file', 'mat/APA300ML.STEP');
+stewart = initializeJointDynamics(stewart, 'type_F', 'flexible', 'K_F', flex_joint.K, 'M_F', flex_joint.M, 'n_xyz_F', flex_joint.n_xyz, 'xi_F', 0.1, 'step_file_F', 'mat/flexor_ID16.STEP', 'type_M', 'flexible', 'K_M', flex_joint.K, 'M_M', flex_joint.M, 'n_xyz_M', flex_joint.n_xyz, 'xi_M', 0.1, 'step_file_M', 'mat/flexor_ID16.STEP');
+stewart = initializeCylindricalPlatforms(stewart, 'Fpr', 150e-3, 'Mpr', 125e-3);
+stewart = initializeCylindricalStruts(stewart, 'type_F', 'none', 'type_M', 'none');
+stewart = computeJacobian(stewart);
+stewart = initializeStewartPose(stewart);
+stewart = initializeInertialSensor(stewart);
ground = initializeGround('type', 'none');
- payload = initializePayload('type', 'rigid', 'm', 50);
- controller = initializeController('type', 'open-loop');
+
ground = initializeGround('type', 'none');
+payload = initializePayload('type', 'rigid', 'm', 50);
+controller = initializeController('type', 'open-loop');
disturbances = initializeDisturbances();
- references = initializeReferences(stewart);
+
disturbances = initializeDisturbances();
+references = initializeReferences(stewart);
-
@@ -144,7 +144,7 @@ Basically, the configuration is stored in a mat file conf_simscape.mat
load('mat/conf_simscape.mat');
+
load('mat/conf_simscape.mat');
set_param
command:
set_param(conf_simscape, 'StopTime', 1);
+
set_param(conf_simscape, 'StopTime', 1);
Function description
-Function description
+ function [payload] = initializePayload(args)
- % initializePayload - Initialize the Payload that can then be used for simulations and analysis
- %
- % Syntax: [payload] = initializePayload(args)
- %
- % Inputs:
- % - args - Structure with the following fields:
- % - type - 'none', 'rigid', 'flexible', 'cartesian'
- % - h [1x1] - Height of the CoM of the payload w.r.t {M} [m]
- % This also the position where K and C are defined
- % - K [6x1] - Stiffness of the Payload [N/m, N/rad]
- % - C [6x1] - Damping of the Payload [N/(m/s), N/(rad/s)]
- % - m [1x1] - Mass of the Payload [kg]
- % - I [3x3] - Inertia matrix for the Payload [kg*m2]
- %
- % Outputs:
- % - payload - Struture with the following properties:
- % - type - 1 (none), 2 (rigid), 3 (flexible)
- % - h [1x1] - Height of the CoM of the payload w.r.t {M} [m]
- % - K [6x1] - Stiffness of the Payload [N/m, N/rad]
- % - C [6x1] - Stiffness of the Payload [N/(m/s), N/(rad/s)]
- % - m [1x1] - Mass of the Payload [kg]
- % - I [3x3] - Inertia matrix for the Payload [kg*m2]
+
function [payload] = initializePayload(args)
+% initializePayload - Initialize the Payload that can then be used for simulations and analysis
+%
+% Syntax: [payload] = initializePayload(args)
+%
+% Inputs:
+% - args - Structure with the following fields:
+% - type - 'none', 'rigid', 'flexible', 'cartesian'
+% - h [1x1] - Height of the CoM of the payload w.r.t {M} [m]
+% This also the position where K and C are defined
+% - K [6x1] - Stiffness of the Payload [N/m, N/rad]
+% - C [6x1] - Damping of the Payload [N/(m/s), N/(rad/s)]
+% - m [1x1] - Mass of the Payload [kg]
+% - I [3x3] - Inertia matrix for the Payload [kg*m2]
+%
+% Outputs:
+% - payload - Struture with the following properties:
+% - type - 1 (none), 2 (rigid), 3 (flexible)
+% - h [1x1] - Height of the CoM of the payload w.r.t {M} [m]
+% - K [6x1] - Stiffness of the Payload [N/m, N/rad]
+% - C [6x1] - Stiffness of the Payload [N/(m/s), N/(rad/s)]
+% - m [1x1] - Mass of the Payload [kg]
+% - I [3x3] - Inertia matrix for the Payload [kg*m2]
Optional Parameters
-Optional Parameters
+ arguments
- args.type char {mustBeMember(args.type,{'none', 'rigid', 'flexible', 'cartesian'})} = 'none'
- args.K (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e8*ones(6,1)
- args.C (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e1*ones(6,1)
- args.h (1,1) double {mustBeNumeric, mustBeNonnegative} = 100e-3
- args.m (1,1) double {mustBeNumeric, mustBeNonnegative} = 10
- args.I (3,3) double {mustBeNumeric, mustBeNonnegative} = 1*eye(3)
- end
+
arguments
+ args.type char {mustBeMember(args.type,{'none', 'rigid', 'flexible', 'cartesian'})} = 'none'
+ args.K (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e8*ones(6,1)
+ args.C (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e1*ones(6,1)
+ args.h (1,1) double {mustBeNumeric, mustBeNonnegative} = 100e-3
+ args.m (1,1) double {mustBeNumeric, mustBeNonnegative} = 10
+ args.I (3,3) double {mustBeNumeric, mustBeNonnegative} = 1*eye(3)
+end
Add Payload Type
switch args.type
- case 'none'
- payload.type = 1;
- case 'rigid'
- payload.type = 2;
- case 'flexible'
- payload.type = 3;
- case 'cartesian'
- payload.type = 4;
- end
+
switch args.type
+ case 'none'
+ payload.type = 1;
+ case 'rigid'
+ payload.type = 2;
+ case 'flexible'
+ payload.type = 3;
+ case 'cartesian'
+ payload.type = 4;
+end
Add Stiffness, Damping and Mass properties of the Payload
payload.K = args.K;
- payload.C = args.C;
- payload.m = args.m;
- payload.I = args.I;
+
payload.K = args.K;
+payload.C = args.C;
+payload.m = args.m;
+payload.I = args.I;
- payload.h = args.h;
+payload.h = args.h;
Function description
-Function description
+ function [ground] = initializeGround(args)
- % initializeGround - Initialize the Ground that can then be used for simulations and analysis
- %
- % Syntax: [ground] = initializeGround(args)
- %
- % Inputs:
- % - args - Structure with the following fields:
- % - type - 'none', 'solid', 'flexible'
- % - rot_point [3x1] - Rotation point for the ground motion [m]
- % - K [3x1] - Translation Stiffness of the Ground [N/m]
- % - C [3x1] - Translation Damping of the Ground [N/(m/s)]
- %
- % Outputs:
- % - ground - Struture with the following properties:
- % - type - 1 (none), 2 (rigid), 3 (flexible)
- % - K [3x1] - Translation Stiffness of the Ground [N/m]
- % - C [3x1] - Translation Damping of the Ground [N/(m/s)]
+
function [ground] = initializeGround(args)
+% initializeGround - Initialize the Ground that can then be used for simulations and analysis
+%
+% Syntax: [ground] = initializeGround(args)
+%
+% Inputs:
+% - args - Structure with the following fields:
+% - type - 'none', 'solid', 'flexible'
+% - rot_point [3x1] - Rotation point for the ground motion [m]
+% - K [3x1] - Translation Stiffness of the Ground [N/m]
+% - C [3x1] - Translation Damping of the Ground [N/(m/s)]
+%
+% Outputs:
+% - ground - Struture with the following properties:
+% - type - 1 (none), 2 (rigid), 3 (flexible)
+% - K [3x1] - Translation Stiffness of the Ground [N/m]
+% - C [3x1] - Translation Damping of the Ground [N/(m/s)]
Optional Parameters
-Optional Parameters
+ arguments
+
arguments
args.type char {mustBeMember(args.type,{'none', 'rigid', 'flexible'})} = 'none'
args.rot_point (3,1) double {mustBeNumeric} = zeros(3,1)
args.K (3,1) double {mustBeNumeric, mustBeNonnegative} = 1e8*ones(3,1)
args.C (3,1) double {mustBeNumeric, mustBeNonnegative} = 1e1*ones(3,1)
- end
+end
Add Ground Type
switch args.type
- case 'none'
- ground.type = 1;
- case 'rigid'
- ground.type = 2;
- case 'flexible'
- ground.type = 3;
- end
+
switch args.type
+ case 'none'
+ ground.type = 1;
+ case 'rigid'
+ ground.type = 2;
+ case 'flexible'
+ ground.type = 3;
+end
Add Stiffness and Damping properties of the Ground
ground.K = args.K;
- ground.C = args.C;
+
ground.K = args.K;
+ground.C = args.C;
Rotation Point
ground.rot_point = args.rot_point;
+
ground.rot_point = args.rot_point;
Function Declaration and Documentation
-Function Declaration and Documentation
+ function [disturbances] = initializeDisturbances(args)
- % initializeDisturbances - Initialize the disturbances
- %
- % Syntax: [disturbances] = initializeDisturbances(args)
- %
- % Inputs:
- % - args -
+
function [disturbances] = initializeDisturbances(args)
+% initializeDisturbances - Initialize the disturbances
+%
+% Syntax: [disturbances] = initializeDisturbances(args)
+%
+% Inputs:
+% - args -
Optional Parameters
-Optional Parameters
+ arguments
+
arguments
args.Fd double {mustBeNumeric, mustBeReal} = zeros(6,1)
args.Fd_t double {mustBeNumeric, mustBeReal} = 0
args.Dw double {mustBeNumeric, mustBeReal} = zeros(6,1)
args.Dw_t double {mustBeNumeric, mustBeReal} = 0
- end
+end
Structure initialization
disturbances = struct();
+
disturbances = struct();
Ground Motion
disturbances.Dw = timeseries([args.Dw], args.Dw_t);
+
disturbances.Dw = timeseries([args.Dw], args.Dw_t);
Direct Forces
disturbances.Fd = timeseries([args.Fd], args.Fd_t);
+
disturbances.Fd = timeseries([args.Fd], args.Fd_t);
Function Declaration and Documentation
-Function Declaration and Documentation
+ function [references] = initializeReferences(stewart, args)
- % initializeReferences - Initialize the references
- %
- % Syntax: [references] = initializeReferences(args)
- %
- % Inputs:
- % - args -
+
function [references] = initializeReferences(stewart, args)
+% initializeReferences - Initialize the references
+%
+% Syntax: [references] = initializeReferences(args)
+%
+% Inputs:
+% - args -
Optional Parameters
-Optional Parameters
+ arguments
+
arguments
stewart
args.t double {mustBeNumeric, mustBeReal} = 0
args.r double {mustBeNumeric, mustBeReal} = zeros(6, 1)
- end
+end
8.1 Compute the corresponding strut length
rL = zeros(6, length(args.t));
+
rL = zeros(6, length(args.t));
- for i = 1:length(args.t)
+for i = 1:length(args.t)
R = [cos(args.r(6,i)) -sin(args.r(6,i)) 0;
sin(args.r(6,i)) cos(args.r(6,i)) 0;
0 0 1] * ...
[cos(args.r(5,i)) 0 sin(args.r(5,i));
0 1 0;
- -sin(args.r(5,i)) 0 cos(args.r(5,i))] * ...
+ -sin(args.r(5,i)) 0 cos(args.r(5,i))] * ...
[1 0 0;
0 cos(args.r(4,i)) -sin(args.r(4,i));
0 sin(args.r(4,i)) cos(args.r(4,i))];
- [Li, dLi] = inverseKinematics(stewart, 'AP', [args.r(1,i); args.r(2,i); args.r(3,i)], 'ARB', R);
- rL(:, i) = dLi;
- end
+ [Li, dLi] = inverseKinematics(stewart, 'AP', [args.r(1,i); args.r(2,i); args.r(3,i)], 'ARB', R);
+ rL(:, i) = dLi;
+end
References
references.r = timeseries(args.r, args.t);
- references.rL = timeseries(rL, args.t);
+
references.r = timeseries(args.r, args.t);
+references.rL = timeseries(rL, args.t);
simulinkproject
function:
simulinkproject('../');
+
simulinkproject('../');
project_startup.m
script.
project = simulinkproject;
- projectRoot = project.RootFolder;
+
project = simulinkproject;
+projectRoot = project.RootFolder;
- myCacheFolder = fullfile(projectRoot, '.SimulinkCache');
- myCodeFolder = fullfile(projectRoot, '.SimulinkCode');
+myCacheFolder = fullfile(projectRoot, '.SimulinkCache');
+myCodeFolder = fullfile(projectRoot, '.SimulinkCode');
- Simulink.fileGenControl('set',...
- 'CacheFolder', myCacheFolder,...
- 'CodeGenFolder', myCodeFolder,...
- 'createDir', true);
+Simulink.fileGenControl('set',...
+ 'CacheFolder', myCacheFolder,...
+ 'CodeGenFolder', myCodeFolder,...
+ 'createDir', true);
- %% Load the Simscape Configuration
- load('mat/conf_simscape.mat');
+%% Load the Simscape Configuration
+load('mat/conf_simscape.mat');
project_startup
When the project closes, it runs the
project_shutdown.m
script defined below.
Simulink.fileGenControl('reset');
+
Simulink.fileGenControl('reset');
initializeStewartPlatform
: Initialize the Stewart Platform structure
initializeFramesPositions
: Initialize the positions of frames {A}, {B}, {F} and {M}
generateGeneralConfiguration
: Generate a Very General Configuration
computeJointsPose
: Compute the Pose of the Joints
-
stewart
structure elementsstewart
structure elementsstewart
structurestewart
structureinitializeStewartPose
: Determine the initial stroke in each leg to have the wanted pose
initializeCylindricalPlatforms
: Initialize the geometry of the Fixed and Mobile Platforms
initializeSolidPlatforms
: Initialize the geometry of the Fixed and Mobile Platforms
initializeCylindricalStruts
: Define the inertia of cylindrical struts
initializeStrutDynamics
: Add Stiffness and Damping properties of each strut
initializeAmplifiedStrutDynamics
: Add Stiffness and Damping properties of each strut for an amplified piezoelectric actuator
initializeFlexibleStrutDynamics
: Model each strut with a flexible element
initializeJointDynamics
: Add Stiffness and Damping properties for spherical joints
initializeFlexibleStrutAndJointDynamics
: Model each strut with a flexible element
initializeInertialSensor
: Initialize the inertial sensor in each strut
displayArchitecture
: 3D plot of the Stewart platform architecture
describeStewartPlatform
: Display some text describing the current defined Stewart Platform
-
stewart
t
Let’s first define the Stewart Platform Geometry.
stewart = initializeStewartPlatform();
- stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
- stewart = generateGeneralConfiguration(stewart);
- stewart = computeJointsPose(stewart);
- stewart = initializeStewartPose(stewart, 'AP', [0;0;0], 'ARB', eye(3));
+
stewart = initializeStewartPlatform();
+stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
+stewart = generateGeneralConfiguration(stewart);
+stewart = computeJointsPose(stewart);
+stewart = initializeStewartPose(stewart, 'AP', [0;0;0], 'ARB', eye(3));
stewart = initializeCylindricalPlatforms(stewart);
- stewart = initializeCylindricalStruts(stewart);
+
stewart = initializeCylindricalPlatforms(stewart);
+stewart = initializeCylindricalStruts(stewart);
stewart = initializeStrutDynamics(stewart, 'K', 1e6*ones(6,1), 'C', 1e2*ones(6,1));
- stewart = initializeAmplifiedStrutDynamics(stewart);
- stewart = initializeJointDynamics(stewart);
+
stewart = initializeStrutDynamics(stewart, 'K', 1e6*ones(6,1), 'C', 1e2*ones(6,1));
+stewart = initializeAmplifiedStrutDynamics(stewart);
+stewart = initializeJointDynamics(stewart);
stewart = initializeInertialSensor(stewart, 'type', 'none');
+
stewart = initializeInertialSensor(stewart, 'type', 'none');
stewart
Matlab structure contains all the information
The function displayArchitecture
can be used to display the current Stewart configuration:
displayArchitecture(stewart, 'views', 'all');
+
displayArchitecture(stewart, 'views', 'all');
tx = 0.1; % [rad]
- ty = 0.2; % [rad]
- tz = 0.05; % [rad]
+
tx = 0.1; % [rad]
+ty = 0.2; % [rad]
+tz = 0.05; % [rad]
- Rx = [1 0 0;
- 0 cos(tx) -sin(tx);
- 0 sin(tx) cos(tx)];
+Rx = [1 0 0;
+ 0 cos(tx) -sin(tx);
+ 0 sin(tx) cos(tx)];
- Ry = [ cos(ty) 0 sin(ty);
- 0 1 0;
- -sin(ty) 0 cos(ty)];
+Ry = [ cos(ty) 0 sin(ty);
+ 0 1 0;
+ -sin(ty) 0 cos(ty)];
- Rz = [cos(tz) -sin(tz) 0;
- sin(tz) cos(tz) 0;
- 0 0 1];
+Rz = [cos(tz) -sin(tz) 0;
+ sin(tz) cos(tz) 0;
+ 0 0 1];
- ARB = Rz*Ry*Rx;
- AP = [0.08; 0; 0]; % [m]
+ARB = Rz*Ry*Rx;
+AP = [0.08; 0; 0]; % [m]
- displayArchitecture(stewart, 'AP', AP, 'ARB', ARB);
- view([0 -1 0]);
+displayArchitecture(stewart, 'AP', AP, 'ARB', ARB);
+view([0 -1 0]);
describeStewartPlatform
function to have a description of the current Stewart platform’s state.
-
+
describeStewartPlatform(stewart)
GEOMETRY:
- The height between the fixed based and the top platform is 90 [mm].
@@ -694,11 +694,11 @@ This Matlab function is accessible
Documentation
-Documentation
+Function description
-Function description
+ 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 -
+
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 -
Initialize the Stewart structure
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();
+
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();
Documentation
-Documentation
+Function description
-Function description
+ function [stewart] = initializeFramesPositions(stewart, args)
- % initializeFramesPositions - Initialize the positions of frames {A}, {B}, {F} and {M}
- %
- % Syntax: [stewart] = initializeFramesPositions(stewart, args)
- %
- % Inputs:
- % - args - Can have the following fields:
- % - H [1x1] - Total Height of the Stewart Platform (height from {F} to {M}) [m]
- % - MO_B [1x1] - Height of the frame {B} with respect to {M} [m]
- %
- % Outputs:
- % - stewart - A structure with the following fields:
- % - geometry.H [1x1] - Total Height of the Stewart Platform [m]
- % - geometry.FO_M [3x1] - Position of {M} with respect to {F} [m]
- % - platform_M.MO_B [3x1] - Position of {B} with respect to {M} [m]
- % - platform_F.FO_A [3x1] - Position of {A} with respect to {F} [m]
+
function [stewart] = initializeFramesPositions(stewart, args)
+% initializeFramesPositions - Initialize the positions of frames {A}, {B}, {F} and {M}
+%
+% Syntax: [stewart] = initializeFramesPositions(stewart, args)
+%
+% Inputs:
+% - args - Can have the following fields:
+% - H [1x1] - Total Height of the Stewart Platform (height from {F} to {M}) [m]
+% - MO_B [1x1] - Height of the frame {B} with respect to {M} [m]
+%
+% Outputs:
+% - stewart - A structure with the following fields:
+% - geometry.H [1x1] - Total Height of the Stewart Platform [m]
+% - geometry.FO_M [3x1] - Position of {M} with respect to {F} [m]
+% - platform_M.MO_B [3x1] - Position of {B} with respect to {M} [m]
+% - platform_F.FO_A [3x1] - Position of {A} with respect to {F} [m]
Optional Parameters
-Optional Parameters
+ arguments
- stewart
- args.H (1,1) double {mustBeNumeric, mustBePositive} = 90e-3
- args.MO_B (1,1) double {mustBeNumeric} = 50e-3
- end
+
arguments
+ stewart
+ args.H (1,1) double {mustBeNumeric, mustBePositive} = 90e-3
+ args.MO_B (1,1) double {mustBeNumeric} = 50e-3
+end
Compute the position of each frame
H = args.H; % Total Height of the Stewart Platform [m]
+
H = args.H; % Total Height of the Stewart Platform [m]
- FO_M = [0; 0; H]; % Position of {M} with respect to {F} [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]
+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]
+FO_A = MO_B + FO_M; % Position of {A} with respect to {F} [m]
Populate the
-stewart
structurePopulate the
+stewart
structure stewart.geometry.H = H;
- stewart.geometry.FO_M = FO_M;
- stewart.platform_M.MO_B = MO_B;
- stewart.platform_F.FO_A = FO_A;
+
stewart.geometry.H = H;
+stewart.geometry.FO_M = FO_M;
+stewart.platform_M.MO_B = MO_B;
+stewart.platform_F.FO_A = FO_A;
Documentation
-Documentation
+Function description
-Function description
+ function [stewart] = generateGeneralConfiguration(stewart, args)
- % generateGeneralConfiguration - Generate a Very General Configuration
- %
- % Syntax: [stewart] = generateGeneralConfiguration(stewart, args)
- %
- % Inputs:
- % - args - Can have the following fields:
- % - FH [1x1] - Height of the position of the fixed joints with respect to the frame {F} [m]
- % - FR [1x1] - Radius of the position of the fixed joints in the X-Y [m]
- % - FTh [6x1] - Angles of the fixed joints in the X-Y plane with respect to the X axis [rad]
- % - MH [1x1] - Height of the position of the mobile joints with respect to the frame {M} [m]
- % - FR [1x1] - Radius of the position of the mobile joints in the X-Y [m]
- % - MTh [6x1] - Angles of the mobile joints in the X-Y plane with respect to the X axis [rad]
- %
- % Outputs:
- % - stewart - updated Stewart structure with the added fields:
- % - platform_F.Fa [3x6] - Its i'th column is the position vector of joint ai with respect to {F}
- % - platform_M.Mb [3x6] - Its i'th column is the position vector of joint bi with respect to {M}
+
function [stewart] = generateGeneralConfiguration(stewart, args)
+% generateGeneralConfiguration - Generate a Very General Configuration
+%
+% Syntax: [stewart] = generateGeneralConfiguration(stewart, args)
+%
+% Inputs:
+% - args - Can have the following fields:
+% - FH [1x1] - Height of the position of the fixed joints with respect to the frame {F} [m]
+% - FR [1x1] - Radius of the position of the fixed joints in the X-Y [m]
+% - FTh [6x1] - Angles of the fixed joints in the X-Y plane with respect to the X axis [rad]
+% - MH [1x1] - Height of the position of the mobile joints with respect to the frame {M} [m]
+% - FR [1x1] - Radius of the position of the mobile joints in the X-Y [m]
+% - MTh [6x1] - Angles of the mobile joints in the X-Y plane with respect to the X axis [rad]
+%
+% Outputs:
+% - stewart - updated Stewart structure with the added fields:
+% - platform_F.Fa [3x6] - Its i'th column is the position vector of joint ai with respect to {F}
+% - platform_M.Mb [3x6] - Its i'th column is the position vector of joint bi with respect to {M}
Optional Parameters
-Optional Parameters
+ arguments
- stewart
- args.FH (1,1) double {mustBeNumeric, mustBePositive} = 15e-3
- args.FR (1,1) double {mustBeNumeric, mustBePositive} = 115e-3;
- args.FTh (6,1) double {mustBeNumeric} = [-10, 10, 120-10, 120+10, 240-10, 240+10]*(pi/180);
- args.MH (1,1) double {mustBeNumeric, mustBePositive} = 15e-3
- args.MR (1,1) double {mustBeNumeric, mustBePositive} = 90e-3;
- args.MTh (6,1) double {mustBeNumeric} = [-60+10, 60-10, 60+10, 180-10, 180+10, -60-10]*(pi/180);
- end
+
arguments
+ stewart
+ args.FH (1,1) double {mustBeNumeric, mustBePositive} = 15e-3
+ args.FR (1,1) double {mustBeNumeric, mustBePositive} = 115e-3;
+ args.FTh (6,1) double {mustBeNumeric} = [-10, 10, 120-10, 120+10, 240-10, 240+10]*(pi/180);
+ args.MH (1,1) double {mustBeNumeric, mustBePositive} = 15e-3
+ args.MR (1,1) double {mustBeNumeric, mustBePositive} = 90e-3;
+ args.MTh (6,1) double {mustBeNumeric} = [-60+10, 60-10, 60+10, 180-10, 180+10, -60-10]*(pi/180);
+end
Compute the pose
Fa = zeros(3,6);
- Mb = zeros(3,6);
+
Fa = zeros(3,6);
+Mb = zeros(3,6);
for i = 1:6
+
for i = 1:6
Fa(:,i) = [args.FR*cos(args.FTh(i)); args.FR*sin(args.FTh(i)); args.FH];
Mb(:,i) = [args.MR*cos(args.MTh(i)); args.MR*sin(args.MTh(i)); -args.MH];
- end
+end
Populate the
-stewart
structurePopulate the
+stewart
structure stewart.platform_F.Fa = Fa;
- stewart.platform_M.Mb = Mb;
+
stewart.platform_F.Fa = Fa;
+stewart.platform_M.Mb = Mb;
Documentation
-Documentation
+Function description
-Function description
+ function [stewart] = computeJointsPose(stewart, args)
- % computeJointsPose -
- %
- % Syntax: [stewart] = computeJointsPose(stewart, args)
- %
- % Inputs:
- % - stewart - A structure with the following fields
- % - platform_F.Fa [3x6] - Its i'th column is the position vector of joint ai with respect to {F}
- % - platform_M.Mb [3x6] - Its i'th column is the position vector of joint bi with respect to {M}
- % - platform_F.FO_A [3x1] - Position of {A} with respect to {F}
- % - platform_M.MO_B [3x1] - Position of {B} with respect to {M}
- % - geometry.FO_M [3x1] - Position of {M} with respect to {F}
- % - 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 - A structure with the following added fields
- % - geometry.Aa [3x6] - The i'th column is the position of ai with respect to {A}
- % - geometry.Ab [3x6] - The i'th column is the position of bi with respect to {A}
- % - geometry.Ba [3x6] - The i'th column is the position of ai with respect to {B}
- % - geometry.Bb [3x6] - The i'th column is the position of bi with respect to {B}
- % - geometry.l [6x1] - The i'th element is the initial length of strut i
- % - geometry.As [3x6] - The i'th column is the unit vector of strut i expressed in {A}
- % - geometry.Bs [3x6] - The i'th column is the unit vector of strut i expressed in {B}
- % - struts_F.l [6x1] - Length of the Fixed part of the i'th strut
- % - struts_M.l [6x1] - Length of the Mobile part of the i'th strut
- % - platform_F.FRa [3x3x6] - The i'th 3x3 array is the rotation matrix to orientate the bottom of the i'th strut from {F}
- % - platform_M.MRb [3x3x6] - The i'th 3x3 array is the rotation matrix to orientate the top of the i'th strut from {M}
+
function [stewart] = computeJointsPose(stewart, args)
+% computeJointsPose -
+%
+% Syntax: [stewart] = computeJointsPose(stewart, args)
+%
+% Inputs:
+% - stewart - A structure with the following fields
+% - platform_F.Fa [3x6] - Its i'th column is the position vector of joint ai with respect to {F}
+% - platform_M.Mb [3x6] - Its i'th column is the position vector of joint bi with respect to {M}
+% - platform_F.FO_A [3x1] - Position of {A} with respect to {F}
+% - platform_M.MO_B [3x1] - Position of {B} with respect to {M}
+% - geometry.FO_M [3x1] - Position of {M} with respect to {F}
+% - 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 - A structure with the following added fields
+% - geometry.Aa [3x6] - The i'th column is the position of ai with respect to {A}
+% - geometry.Ab [3x6] - The i'th column is the position of bi with respect to {A}
+% - geometry.Ba [3x6] - The i'th column is the position of ai with respect to {B}
+% - geometry.Bb [3x6] - The i'th column is the position of bi with respect to {B}
+% - geometry.l [6x1] - The i'th element is the initial length of strut i
+% - geometry.As [3x6] - The i'th column is the unit vector of strut i expressed in {A}
+% - geometry.Bs [3x6] - The i'th column is the unit vector of strut i expressed in {B}
+% - struts_F.l [6x1] - Length of the Fixed part of the i'th strut
+% - struts_M.l [6x1] - Length of the Mobile part of the i'th strut
+% - platform_F.FRa [3x3x6] - The i'th 3x3 array is the rotation matrix to orientate the bottom of the i'th strut from {F}
+% - platform_M.MRb [3x3x6] - The i'th 3x3 array is the rotation matrix to orientate the top of the i'th strut from {M}
Optional Parameters
-Optional Parameters
+ arguments
- stewart
- args.AP (3,1) double {mustBeNumeric} = zeros(3,1)
- args.ARB (3,3) double {mustBeNumeric} = eye(3)
- end
+
arguments
+ stewart
+ args.AP (3,1) double {mustBeNumeric} = zeros(3,1)
+ args.ARB (3,3) double {mustBeNumeric} = eye(3)
+end
Check the
-stewart
structure elementsCheck the
+stewart
structure elements assert(isfield(stewart.platform_F, 'Fa'), 'stewart.platform_F should have attribute Fa')
- Fa = stewart.platform_F.Fa;
+
assert(isfield(stewart.platform_F, 'Fa'), 'stewart.platform_F should have attribute Fa')
+Fa = stewart.platform_F.Fa;
- assert(isfield(stewart.platform_M, 'Mb'), 'stewart.platform_M should have attribute Mb')
- Mb = stewart.platform_M.Mb;
+assert(isfield(stewart.platform_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_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.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;
+assert(isfield(stewart.geometry, 'FO_M'), 'stewart.geometry should have attribute FO_M')
+FO_M = stewart.geometry.FO_M;
Compute the position of the Joints
Aa = Fa - repmat(FO_A, [1, 6]);
- Bb = Mb - repmat(MO_B, [1, 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]);
+
Ab = Bb - repmat(-MO_B-FO_M+FO_A, [1, 6]);
+Ba = Aa - repmat( MO_B+FO_M-FO_A, [1, 6]);
Ab = args.ARB *Bb - repmat(-args.AP, [1, 6]);
- Ba = args.ARB'*Aa - repmat( args.AP, [1, 6]);
+
Ab = args.ARB *Bb - repmat(-args.AP, [1, 6]);
+Ba = args.ARB'*Aa - repmat( args.AP, [1, 6]);
Compute the strut length and orientation
As = (Ab - Aa)./vecnorm(Ab - 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
- l = vecnorm(Ab - Aa)';
+l = vecnorm(Ab - Aa)';
Bs = (Bb - Ba)./vecnorm(Bb - Ba);
+
Bs = (Bb - Ba)./vecnorm(Bb - Ba);
Compute the orientation of the Joints
FRa = zeros(3,3,6);
- MRb = zeros(3,3,6);
+
FRa = zeros(3,3,6);
+MRb = zeros(3,3,6);
- for i = 1:6
+for i = 1:6
FRa(:,:,i) = [cross([0;1;0], As(:,i)) , cross(As(:,i), cross([0;1;0], As(:,i))) , As(:,i)];
FRa(:,:,i) = FRa(:,:,i)./vecnorm(FRa(:,:,i));
MRb(:,:,i) = [cross([0;1;0], Bs(:,i)) , cross(Bs(:,i), cross([0;1;0], Bs(:,i))) , Bs(:,i)];
MRb(:,:,i) = MRb(:,:,i)./vecnorm(MRb(:,:,i));
- end
+end
Populate the
-stewart
structurePopulate the
+stewart
structure 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.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.struts_F.l = l/2;
+stewart.struts_M.l = l/2;
- stewart.platform_F.FRa = FRa;
- stewart.platform_M.MRb = MRb;
+stewart.platform_F.FRa = FRa;
+stewart.platform_M.MRb = MRb;
Function description
-Function description
+ 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}
+
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}
Optional Parameters
-Optional Parameters
+ arguments
- stewart
- args.AP (3,1) double {mustBeNumeric} = zeros(3,1)
- args.ARB (3,3) double {mustBeNumeric} = eye(3)
- end
+
arguments
+ stewart
+ args.AP (3,1) double {mustBeNumeric} = zeros(3,1)
+ args.ARB (3,3) double {mustBeNumeric} = eye(3)
+end
Use the Inverse Kinematic function
[Li, dLi] = inverseKinematics(stewart, 'AP', args.AP, 'ARB', args.ARB);
+
[Li, dLi] = inverseKinematics(stewart, 'AP', args.AP, 'ARB', args.ARB);
Populate the
-stewart
structurePopulate the
+stewart
structure stewart.actuators.Leq = dLi;
+
stewart.actuators.Leq = dLi;
Function description
-Function description
+ function [stewart] = initializeCylindricalPlatforms(stewart, args)
- % initializeCylindricalPlatforms - Initialize the geometry of the Fixed and Mobile Platforms
- %
- % Syntax: [stewart] = initializeCylindricalPlatforms(args)
- %
- % Inputs:
- % - args - Structure with the following fields:
- % - Fpm [1x1] - Fixed Platform Mass [kg]
- % - Fph [1x1] - Fixed Platform Height [m]
- % - Fpr [1x1] - Fixed Platform Radius [m]
- % - Mpm [1x1] - Mobile Platform Mass [kg]
- % - Mph [1x1] - Mobile Platform Height [m]
- % - Mpr [1x1] - Mobile Platform Radius [m]
- %
- % Outputs:
- % - stewart - updated Stewart structure with the added fields:
- % - platform_F [struct] - structure with the following fields:
- % - type = 1
- % - M [1x1] - Fixed Platform Mass [kg]
- % - I [3x3] - Fixed Platform Inertia matrix [kg*m^2]
- % - H [1x1] - Fixed Platform Height [m]
- % - R [1x1] - Fixed Platform Radius [m]
- % - platform_M [struct] - structure with the following fields:
- % - M [1x1] - Mobile Platform Mass [kg]
- % - I [3x3] - Mobile Platform Inertia matrix [kg*m^2]
- % - H [1x1] - Mobile Platform Height [m]
- % - R [1x1] - Mobile Platform Radius [m]
+
function [stewart] = initializeCylindricalPlatforms(stewart, args)
+% initializeCylindricalPlatforms - Initialize the geometry of the Fixed and Mobile Platforms
+%
+% Syntax: [stewart] = initializeCylindricalPlatforms(args)
+%
+% Inputs:
+% - args - Structure with the following fields:
+% - Fpm [1x1] - Fixed Platform Mass [kg]
+% - Fph [1x1] - Fixed Platform Height [m]
+% - Fpr [1x1] - Fixed Platform Radius [m]
+% - Mpm [1x1] - Mobile Platform Mass [kg]
+% - Mph [1x1] - Mobile Platform Height [m]
+% - Mpr [1x1] - Mobile Platform Radius [m]
+%
+% Outputs:
+% - stewart - updated Stewart structure with the added fields:
+% - platform_F [struct] - structure with the following fields:
+% - type = 1
+% - M [1x1] - Fixed Platform Mass [kg]
+% - I [3x3] - Fixed Platform Inertia matrix [kg*m^2]
+% - H [1x1] - Fixed Platform Height [m]
+% - R [1x1] - Fixed Platform Radius [m]
+% - platform_M [struct] - structure with the following fields:
+% - M [1x1] - Mobile Platform Mass [kg]
+% - I [3x3] - Mobile Platform Inertia matrix [kg*m^2]
+% - H [1x1] - Mobile Platform Height [m]
+% - R [1x1] - Mobile Platform Radius [m]
Optional Parameters
-Optional Parameters
+ arguments
- stewart
- args.Fpm (1,1) double {mustBeNumeric, mustBePositive} = 1
- args.Fph (1,1) double {mustBeNumeric, mustBePositive} = 10e-3
- args.Fpr (1,1) double {mustBeNumeric, mustBePositive} = 125e-3
- args.Mpm (1,1) double {mustBeNumeric, mustBePositive} = 1
- args.Mph (1,1) double {mustBeNumeric, mustBePositive} = 10e-3
- args.Mpr (1,1) double {mustBeNumeric, mustBePositive} = 100e-3
- end
+
arguments
+ stewart
+ args.Fpm (1,1) double {mustBeNumeric, mustBePositive} = 1
+ args.Fph (1,1) double {mustBeNumeric, mustBePositive} = 10e-3
+ args.Fpr (1,1) double {mustBeNumeric, mustBePositive} = 125e-3
+ args.Mpm (1,1) double {mustBeNumeric, mustBePositive} = 1
+ args.Mph (1,1) double {mustBeNumeric, mustBePositive} = 10e-3
+ args.Mpr (1,1) double {mustBeNumeric, mustBePositive} = 100e-3
+end
I_F = diag([1/12*args.Fpm * (3*args.Fpr^2 + args.Fph^2), ...
- 1/12*args.Fpm * (3*args.Fpr^2 + args.Fph^2), ...
- 1/2 *args.Fpm * args.Fpr^2]);
+
I_F = diag([1/12*args.Fpm * (3*args.Fpr^2 + args.Fph^2), ...
+ 1/12*args.Fpm * (3*args.Fpr^2 + args.Fph^2), ...
+ 1/2 *args.Fpm * args.Fpr^2]);
I_M = diag([1/12*args.Mpm * (3*args.Mpr^2 + args.Mph^2), ...
- 1/12*args.Mpm * (3*args.Mpr^2 + args.Mph^2), ...
- 1/2 *args.Mpm * args.Mpr^2]);
+
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]);
Populate the
-stewart
structurePopulate the
+stewart
structure stewart.platform_F.type = 1;
+
stewart.platform_F.type = 1;
- stewart.platform_F.I = I_F;
- stewart.platform_F.M = args.Fpm;
- stewart.platform_F.R = args.Fpr;
- stewart.platform_F.H = args.Fph;
+stewart.platform_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.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;
+stewart.platform_M.I = I_M;
+stewart.platform_M.M = args.Mpm;
+stewart.platform_M.R = args.Mpr;
+stewart.platform_M.H = args.Mph;
Function description
-Function description
+ function [stewart] = initializeSolidPlatforms(stewart, args)
- % initializeSolidPlatforms - Initialize the geometry of the Fixed and Mobile Platforms
- %
- % Syntax: [stewart] = initializeSolidPlatforms(args)
- %
- % Inputs:
- % - args - Structure with the following fields:
- % - density [1x1] - Density of the platforms [kg]
- %
- % Outputs:
- % - stewart - updated Stewart structure with the added fields:
- % - platform_F [struct] - structure with the following fields:
- % - type = 2
- % - M [1x1] - Fixed Platform Density [kg/m^3]
- % - platform_M [struct] - structure with the following fields:
- % - type = 2
- % - M [1x1] - Mobile Platform Density [kg/m^3]
+
function [stewart] = initializeSolidPlatforms(stewart, args)
+% initializeSolidPlatforms - Initialize the geometry of the Fixed and Mobile Platforms
+%
+% Syntax: [stewart] = initializeSolidPlatforms(args)
+%
+% Inputs:
+% - args - Structure with the following fields:
+% - density [1x1] - Density of the platforms [kg]
+%
+% Outputs:
+% - stewart - updated Stewart structure with the added fields:
+% - platform_F [struct] - structure with the following fields:
+% - type = 2
+% - M [1x1] - Fixed Platform Density [kg/m^3]
+% - platform_M [struct] - structure with the following fields:
+% - type = 2
+% - M [1x1] - Mobile Platform Density [kg/m^3]
Optional Parameters
-Optional Parameters
+ arguments
- stewart
- args.density (1,1) double {mustBeNumeric, mustBePositive} = 7800
- end
+
arguments
+ stewart
+ args.density (1,1) double {mustBeNumeric, mustBePositive} = 7800
+end
Populate the
-stewart
structurePopulate the
+stewart
structure stewart.platform_F.type = 2;
+
stewart.platform_F.type = 2;
- stewart.platform_F.density = args.density;
+stewart.platform_F.density = args.density;
stewart.platform_M.type = 2;
+
stewart.platform_M.type = 2;
- stewart.platform_M.density = args.density;
+stewart.platform_M.density = args.density;
Function description
-Function description
+ function [stewart] = initializeCylindricalStruts(stewart, args)
- % initializeCylindricalStruts - Define the mass and moment of inertia of cylindrical struts
- %
- % Syntax: [stewart] = initializeCylindricalStruts(args)
- %
- % Inputs:
- % - args - Structure with the following fields:
- % - Fsm [1x1] - Mass of the Fixed part of the struts [kg]
- % - Fsh [1x1] - Height of cylinder for the Fixed part of the struts [m]
- % - Fsr [1x1] - Radius of cylinder for the Fixed part of the struts [m]
- % - Msm [1x1] - Mass of the Mobile part of the struts [kg]
- % - Msh [1x1] - Height of cylinder for the Mobile part of the struts [m]
- % - Msr [1x1] - Radius of cylinder for the Mobile part of the struts [m]
- %
- % Outputs:
- % - stewart - updated Stewart structure with the added fields:
- % - struts_F [struct] - structure with the following fields:
- % - M [6x1] - Mass of the Fixed part of the struts [kg]
- % - I [3x3x6] - Moment of Inertia for the Fixed part of the struts [kg*m^2]
- % - H [6x1] - Height of cylinder for the Fixed part of the struts [m]
- % - R [6x1] - Radius of cylinder for the Fixed part of the struts [m]
- % - struts_M [struct] - structure with the following fields:
- % - M [6x1] - Mass of the Mobile part of the struts [kg]
- % - I [3x3x6] - Moment of Inertia for the Mobile part of the struts [kg*m^2]
- % - H [6x1] - Height of cylinder for the Mobile part of the struts [m]
- % - R [6x1] - Radius of cylinder for the Mobile part of the struts [m]
+