From b5b3a756a48cad0efe1ea2bbb12dd589178dc7a6 Mon Sep 17 00:00:00 2001 From: Thomas Dehaeze Date: Thu, 13 Feb 2020 16:46:47 +0100 Subject: [PATCH] Add link to tangled files --- docs/active-damping.html | 103 ++++-- docs/cubic-configuration.html | 94 ++++- docs/kinematic-study.html | 224 +++++++----- matlab/active_damping_dvf.m | 86 +++-- matlab/active_damping_iff.m | 65 +++- matlab/active_damping_inertial.m | 88 +++-- matlab/cubic_conf_above_platforml.m | 93 +++++ matlab/cubic_conf_coupling_cartesianl.m | 336 ++++++++++++++++++ matlab/cubic_conf_coupling_strutsl.m | 301 ++++++++++++++++ matlab/cubic_conf_size_analysisl.m | 51 +++ matlab/cubic_conf_stiffnessl.m | 96 +++++ ... kinematic_study_approximation_validity.m} | 11 +- ...or_stroke.m => kinematic_study_mobility.m} | 13 +- ...inematic_study_required_actuator_stroke.m} | 23 +- org/active-damping.org | 18 + org/cubic-configuration.org | 55 +++ org/kinematic-study.org | 47 ++- 17 files changed, 1423 insertions(+), 281 deletions(-) create mode 100644 matlab/cubic_conf_above_platforml.m create mode 100644 matlab/cubic_conf_coupling_cartesianl.m create mode 100644 matlab/cubic_conf_coupling_strutsl.m create mode 100644 matlab/cubic_conf_size_analysisl.m create mode 100644 matlab/cubic_conf_stiffnessl.m rename matlab/{approximate_inverse_kinematics_validity.m => kinematic_study_approximation_validity.m} (87%) rename matlab/{mobility_from_actuator_stroke.m => kinematic_study_mobility.m} (84%) rename matlab/{required_stroke_from_mobility.m => kinematic_study_required_actuator_stroke.m} (88%) diff --git a/docs/active-damping.html b/docs/active-damping.html index 06f97dd..fd80668 100644 --- a/docs/active-damping.html +++ b/docs/active-damping.html @@ -4,7 +4,7 @@ "http://www.w3.org/TR/xhtml1/DTD/xhtml1-strict.dtd"> - + Stewart Platform - Decentralized Active Damping @@ -271,25 +271,25 @@ for the JavaScript code in this tag.
  • 1. Inertial Control
  • 2. Integral Force Feedback
  • 3. Direct Velocity Feedback
  • @@ -311,6 +311,17 @@ The following decentralized active damping techniques are briefly studied:

    + +
    +

    +The Matlab script corresponding to this section is accessible here. +

    + +

    +To run the script, open the Simulink Project, and type run active_damping_inertial.m. +

    + +
    @@ -369,8 +380,8 @@ The transfer function from actuator forces to force sensors is shown in Figure <
    -
    -

    1.2 Effect of the Flexible Joint stiffness and Actuator amplification on the Dynamics

    +
    +

    1.2 Effect of the Flexible Joint stiffness and Actuator amplification on the Dynamics

    We add some stiffness and damping in the flexible joints and we re-identify the dynamics. @@ -406,8 +417,8 @@ The new dynamics from force actuator to force sensor is shown in Figure

    -
    -

    1.3 Obtained Damping

    +
    -
    -

    1.4 Conclusion

    +
    +

    1.4 Conclusion

    @@ -451,10 +462,21 @@ We do not have guaranteed stability with Inertial control. This is because of th

    + +
    +

    +The Matlab script corresponding to this section is accessible here. +

    + +

    +To run the script, open the Simulink Project, and type run active_damping_iff.m. +

    + +
    -
    -

    2.1 Identification of the Dynamics with perfect Joints

    +
    +

    2.1 Identification of the Dynamics with perfect Joints

    We first initialize the Stewart platform without joint stiffness. @@ -515,8 +537,8 @@ The transfer function from actuator forces to force sensors is shown in Figure <

    -
    -

    2.2 Effect of the Flexible Joint stiffness and Actuator amplification on the Dynamics

    +
    +

    2.2 Effect of the Flexible Joint stiffness and Actuator amplification on the Dynamics

    We add some stiffness and damping in the flexible joints and we re-identify the dynamics. @@ -552,8 +574,8 @@ The new dynamics from force actuator to force sensor is shown in Figure

    -
    -

    2.3 Obtained Damping

    +
    -
    -

    2.4 Conclusion

    +
    +

    2.4 Conclusion

    @@ -605,10 +627,21 @@ 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. +

    + +

    +To run the script, open the Simulink Project, and type run active_damping_dvf.m. +

    + +
    -
    -

    3.1 Identification of the Dynamics with perfect Joints

    +
    +

    3.1 Identification of the Dynamics with perfect Joints

    We first initialize the Stewart platform without joint stiffness. @@ -670,8 +703,8 @@ The transfer function from actuator forces to relative motion sensors is shown i

    -
    -

    3.2 Effect of the Flexible Joint stiffness and Actuator amplification on the Dynamics

    +
    +

    3.2 Effect of the Flexible Joint stiffness and Actuator amplification on the Dynamics

    We add some stiffness and damping in the flexible joints and we re-identify the dynamics. @@ -707,8 +740,8 @@ The new dynamics from force actuator to relative motion sensor is shown in Figur

    -
    -

    3.3 Obtained Damping

    +
    +

    3.3 Obtained Damping

    The control is a performed in a decentralized manner. @@ -733,8 +766,8 @@ The root locus is shown in figure 10.

    -
    -

    3.4 Conclusion

    +
    +

    3.4 Conclusion

    @@ -748,7 +781,7 @@ Joint stiffness does increase the resonance frequencies of the system but does n

    Author: Dehaeze Thomas

    -

    Created: 2020-02-13 jeu. 14:50

    +

    Created: 2020-02-13 jeu. 16:46

    diff --git a/docs/cubic-configuration.html b/docs/cubic-configuration.html index 8303f92..9787df1 100644 --- a/docs/cubic-configuration.html +++ b/docs/cubic-configuration.html @@ -4,7 +4,7 @@ "http://www.w3.org/TR/xhtml1/DTD/xhtml1-strict.dtd"> - + Cubic configuration for the Stewart Platform @@ -274,33 +274,33 @@ for the JavaScript code in this tag.
  • 1.2. Cubic Stewart platform centered with the cube center - Jacobian not estimated at the cube center
  • 1.3. Cubic Stewart platform not centered with the cube center - Jacobian estimated at the cube center
  • 1.4. Cubic Stewart platform not centered with the cube center - Jacobian estimated at the Stewart platform center
  • -
  • 1.5. Conclusion
  • +
  • 1.5. Conclusion
  • 2. Configuration with the Cube’s center above the mobile platform
  • 3. Cubic size analysis
  • 4. Dynamic Coupling in the Cartesian Frame
  • 5. Dynamic Coupling between actuators and sensors of each strut
  • 6. Functions @@ -355,6 +355,17 @@ In this document, the cubic architecture is analyzed:

    + +
    +

    +The Matlab script corresponding to this section is accessible here. +

    + +

    +To run the script, open the Simulink Project, and type run cubic_conf_stiffness.m. +

    + +

    First, we have to understand what is the physical meaning of the Stiffness matrix \(\bm{K}\).

    @@ -389,6 +400,7 @@ One has to note that this is only valid in a static way. We here study what makes the Stiffness matrix diagonal when using a cubic configuration.

  • +

    1.1 Cubic Stewart platform centered with the cube center - Jacobian estimated at the cube center

    @@ -836,8 +848,8 @@ stewart = initializeCylindricalPlatforms(stewart, 'Fpr'
    -
    -

    1.5 Conclusion

    +
    +

    1.5 Conclusion

    @@ -859,6 +871,17 @@ Here are the conclusion about the Stiffness matrix for the Cubic configuration:

    + +
    +

    +The Matlab script corresponding to this section is accessible here. +

    + +

    +To run the script, open the Simulink Project, and type run cubic_conf_above_platform.m. +

    + +

    We saw in section 1 that in order to have a diagonal stiffness matrix, we need the cube’s center to be located at frames \(\{A\}\) and \(\{B\}\). Or, we usually want to have \(\{A\}\) and \(\{B\}\) located above the top platform where forces are applied and where displacements are expressed. @@ -868,6 +891,7 @@ Or, we usually want to have \(\{A\}\) and \(\{B\}\) located above the top platfo We here see if the cubic configuration can provide a diagonal stiffness matrix when \(\{A\}\) and \(\{B\}\) are above the mobile platform.

    +

    2.1 Having Cube’s center above the top platform

    @@ -1162,8 +1186,8 @@ FOc = H + MO_B; % Cente
    -
    -

    2.2 Conclusion

    +
    +

    2.2 Conclusion

    @@ -1182,6 +1206,17 @@ Depending on the cube’s size, we obtain 3 different configurations.

    + +
    +

    +The Matlab script corresponding to this section is accessible here. +

    + +

    +To run the script, open the Simulink Project, and type run cubic_conf_size_analysis.m. +

    + +

    We here study the effect of the size of the cube used for the Stewart Cubic configuration.

    @@ -1194,6 +1229,7 @@ We fix the height of the Stewart platform, the center of the cube is at the cent We only vary the size of the cube.

    +

    3.1 Analysis

    @@ -1237,8 +1273,8 @@ We also find that \(k_{\theta_x} = k_{\theta_y}\) and \(k_{\theta_z}\) are varyi
    -
    -

    3.2 Conclusion

    +
    +

    3.2 Conclusion

    We observe that \(k_{\theta_x} = k_{\theta_y}\) and \(k_{\theta_z}\) increase linearly with the cube size. @@ -1260,6 +1296,17 @@ In order to maximize the rotational stiffness of the Stewart platform, the size

    + +
    +

    +The Matlab script corresponding to this section is accessible here. +

    + +

    +To run the script, open the Simulink Project, and type run cubic_conf_coupling_cartesian.m. +

    + +

    In this section, we study the dynamics of the platform in the cartesian frame.

    @@ -1316,6 +1363,7 @@ We conclude that the static behavior of the platform depends on the stiff For the cubic configuration, we have a diagonal stiffness matrix is the frames \(\{A\}\) and \(\{B\}\) are coincident with the cube’s center.

    +

    4.1 Cube’s center at the Center of Mass of the mobile platform

    @@ -1595,8 +1643,8 @@ This was expected as the mass matrix is not diagonal (the Center of Mass of the
    -
    -

    4.3 Conclusion

    +
    +

    4.3 Conclusion

    @@ -1618,6 +1666,17 @@ Some conclusions can be drawn from the above analysis:

    + +
    +

    +The Matlab script corresponding to this section is accessible here. +

    + +

    +To run the script, open the Simulink Project, and type run cubic_conf_coupling_struts.m. +

    + +

    From preumont07_six_axis_singl_stage_activ, the cubic configuration “minimizes the cross-coupling amongst actuators and sensors of different legs (being orthogonal to each other)”.

    @@ -1630,6 +1689,7 @@ In this section, we wish to study such properties of the cubic architecture. We will compare the transfer function from sensors to actuators in each strut for a cubic architecture and for a non-cubic architecture (where the struts are not orthogonal with each other).

    +

    5.1 Coupling between the actuators and sensors - Cubic Architecture

    @@ -1766,8 +1826,8 @@ And we identify the dynamics from the actuator forces \(\tau_{i}\) to the relati
    -
    -

    5.3 Conclusion

    +
    +

    5.3 Conclusion

    @@ -1938,7 +1998,7 @@ stewart.platform_M.Mb = Mb;

    Author: Dehaeze Thomas

    -

    Created: 2020-02-13 jeu. 15:01

    +

    Created: 2020-02-13 jeu. 16:46

    diff --git a/docs/kinematic-study.html b/docs/kinematic-study.html index 7299e89..34a9811 100644 --- a/docs/kinematic-study.html +++ b/docs/kinematic-study.html @@ -4,7 +4,7 @@ "http://www.w3.org/TR/xhtml1/DTD/xhtml1-strict.dtd"> - + Kinematic Study of the Stewart Platform @@ -285,55 +285,55 @@ for the JavaScript code in this tag.
  • 3.1. Inverse Kinematics
  • 3.2. Forward Kinematics
  • 3.3. Approximate solution of the Forward and Inverse Kinematic problem for small displacement using the Jacobian matrix
  • -
  • 3.4. Estimation of the range validity of the approximate inverse kinematics -
  • +
  • 4. Estimation of the range validity of the approximate inverse kinematics +
  • -
  • 4. Estimated required actuator stroke from specified platform mobility +
  • 5. Estimated required actuator stroke from specified platform mobility
  • -
  • 5. Estimated platform mobility from specified actuator stroke +
  • 6. Estimated platform mobility from specified actuator stroke
  • -
  • 6. Functions +
  • 7. Functions
    @@ -647,13 +648,25 @@ The function forwardKinematicsApprox (described -

    3.4 Estimation of the range validity of the approximate inverse kinematics

    -
    +
    +

    4 Estimation of the range validity of the approximate inverse kinematics

    +

    - +

    + +
    +

    +The Matlab script corresponding to this section is accessible here. +

    + +

    +To run the script, open the Simulink Project, and type run kinematic_study_approximation_validity.m. +

    + +

    As we know how to exactly solve the Inverse kinematic problem, we can compare the exact solution with the approximate solution using the Jacobian matrix. For small displacements, the approximate solution is expected to work well. @@ -666,9 +679,9 @@ This will also gives us the range for which the approximate forward kinematic is

    -
    -

    3.4.1 Stewart architecture definition

    -
    +
    +

    4.1 Stewart architecture definition

    +

    We first define some general Stewart architecture.

    @@ -688,9 +701,9 @@ stewart = computeJacobian(stewart);
    -
    -

    3.4.2 Comparison for “pure” translations

    -
    +
    +

    4.2 Comparison for “pure” translations

    +

    Let’s first compare the perfect and approximate solution of the inverse for pure \(x\) translations.

    @@ -730,9 +743,9 @@ Ls_exact = zeros(6, length(Xrs));
    -
    -

    3.4.3 Conclusion

    -
    +
    +

    4.3 Conclusion

    +

    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. @@ -742,23 +755,34 @@ For small wanted displacements (up to \(\approx 1\%\) of the size of the Hexapod

    -
    -

    4 Estimated required actuator stroke from specified platform mobility

    -
    +

    5 Estimated required actuator stroke from specified platform mobility

    +

    - +

    + +
    +

    +The Matlab script corresponding to this section is accessible here. +

    + +

    +To run the script, open the Simulink Project, and type run kinematic_study_required_actuator_stroke.m. +

    + +

    Let’s say one want to design a Stewart platform with some specified mobility (position and orientation). One may want to determine the required actuator stroke required to obtain the specified mobility. This is what is analyzed in this section.

    -
    -

    4.1 Stewart architecture definition

    -
    + +
    +

    5.1 Stewart architecture definition

    +

    Let’s first define the Stewart platform architecture that we want to study.

    @@ -779,8 +803,8 @@ stewart = computeJacobian(stewart);
    -

    4.2 Wanted translations and rotations

    -
    +

    5.2 Wanted translations and rotations

    +

    Let’s now define the wanted extreme translations and rotations.

    @@ -797,8 +821,8 @@ Rz_max = 0; % Rotation [rad]
    -

    4.3 Needed stroke for “pure” rotations or translations

    -
    +

    5.3 Needed stroke for “pure” rotations or translations

    +

    As a first estimation, we estimate the needed actuator stroke for “pure” rotations and translation. We do that using either the Inverse Kinematic solution or the Jacobian matrix as an approximation. @@ -829,8 +853,8 @@ This is surely a low estimation of the required stroke.

    -

    4.4 Needed stroke for “combined” rotations or translations

    -
    +

    5.4 Needed stroke for “combined” rotations or translations

    +

    We know would like to have a more precise estimation.

    @@ -1150,11 +1174,22 @@ This is probably a much realistic estimation of the required actuator stroke.
    -

    5 Estimated platform mobility from specified actuator stroke

    -
    +

    6 Estimated platform mobility from specified actuator stroke

    +

    - +

    + +
    +

    +The Matlab script corresponding to this section is accessible here. +

    + +

    +To run the script, open the Simulink Project, and type run kinematic_study_mobility.m. +

    + +

    Here, from some value of the actuator stroke, we would like to estimate the mobility of the Stewart platform.

    @@ -1164,9 +1199,10 @@ As explained in section 3, the forward kinematic probl However, for small displacements, we can use the Jacobian as an approximate solution.

    -
    -

    5.1 Stewart architecture definition

    -
    + +
    +

    6.1 Stewart architecture definition

    +

    Let’s first define the Stewart platform architecture that we want to study.

    @@ -1196,8 +1232,8 @@ L_max = 50e-6; % [m]
    -

    5.2 Pure translations

    -
    +

    6.2 Pure translations

    +

    Let’s first estimate the mobility in translation when the orientation of the Stewart platform stays the same.

    @@ -1278,15 +1314,15 @@ We can also approximate the mobility by a sphere with a radius equal to the mini
    -

    6 Functions

    -
    +

    7 Functions

    +

    -

    6.1 computeJacobian: Compute the Jacobian Matrix

    -
    +

    7.1 computeJacobian: Compute the Jacobian Matrix

    +

    @@ -1296,9 +1332,9 @@ This Matlab function is accessible here.

    -
    -

    Function description

    -
    +
    +

    Function description

    +
    function [stewart] = computeJacobian(stewart)
     % computeJacobian -
    @@ -1321,9 +1357,9 @@ This Matlab function is accessible here.
     
    -
    -

    Check the stewart structure elements

    -
    +
    +

    Check the stewart structure elements

    +
    assert(isfield(stewart.geometry, 'As'),   'stewart.geometry should have attribute As')
     As = stewart.geometry.As;
    @@ -1384,8 +1420,8 @@ stewart.kinematics.C = C;
     
     
     
    -

    6.2 inverseKinematics: Compute Inverse Kinematics

    -
    +

    7.2 inverseKinematics: Compute Inverse Kinematics

    +

    @@ -1431,9 +1467,9 @@ Otherwise, when the limbs’ lengths derived yield complex numbers, then the
    -
    -

    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}
    @@ -1457,9 +1493,9 @@ Otherwise, when the limbs’ lengths derived yield complex numbers, then the
     
    -
    -

    Optional Parameters

    -
    +
    +

    Optional Parameters

    +
    arguments
         stewart
    @@ -1471,9 +1507,9 @@ Otherwise, when the limbs’ lengths derived yield complex numbers, then the
     
    -
    -

    Check the stewart structure elements

    -
    +
    +

    Check the stewart structure elements

    +
    assert(isfield(stewart.geometry, 'Aa'),   'stewart.geometry should have attribute Aa')
     Aa = stewart.geometry.Aa;
    @@ -1506,8 +1542,8 @@ l = stewart.geometry.l;
     
    -

    6.3 forwardKinematicsApprox: Compute the Approximate Forward Kinematics

    -
    +

    7.3 forwardKinematicsApprox: Compute the Approximate Forward Kinematics

    +

    @@ -1517,9 +1553,9 @@ This Matlab function is accessible he

    -
    -

    Function description

    -
    +
    +

    Function description

    +
    -
    -

    Optional Parameters

    -
    +
    +

    Optional Parameters

    +
    -
    -

    Check the stewart structure elements

    -
    +
    +

    Check the stewart structure elements

    +
    assert(isfield(stewart.kinematics, 'J'),   'stewart.kinematics should have attribute J')
     J = stewart.kinematics.J;
    @@ -1619,7 +1655,7 @@ We then compute the corresponding rotation matrix.
     

    Author: Dehaeze Thomas

    -

    Created: 2020-02-12 mer. 10:22

    +

    Created: 2020-02-13 jeu. 16:46

    diff --git a/matlab/active_damping_dvf.m b/matlab/active_damping_dvf.m index 474f4b9..ff1fbd2 100644 --- a/matlab/active_damping_dvf.m +++ b/matlab/active_damping_dvf.m @@ -4,22 +4,27 @@ clear; close all; clc; %% Intialize Laplace variable s = zpk('s'); -simulinkproject('./'); +simulinkproject('../'); -open('simulink/stewart_active_damping.slx') +open('stewart_platform_model.slx') % Identification of the Dynamics with perfect Joints % We first initialize the Stewart platform without joint stiffness. -stewart = initializeFramesPositions('H', 90e-3, 'MO_B', 45e-3); +stewart = initializeStewartPlatform(); +stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3); stewart = generateGeneralConfiguration(stewart); stewart = computeJointsPose(stewart); stewart = initializeStrutDynamics(stewart); -stewart = initializeJointDynamics(stewart, 'disable', true); +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'); @@ -30,12 +35,12 @@ options = linearizeOptions; options.SampleTime = 0; %% Name of the Simulink File -mdl = 'stewart_active_damping'; +mdl = 'stewart_platform_model'; %% Input/Output definition clear io; io_i = 1; -io(io_i) = linio([mdl, '/F'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N] -io(io_i) = linio([mdl, '/Dm'], 1, 'openoutput'); io_i = io_i + 1; % Relative Displacement Outputs [N] +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); @@ -46,7 +51,7 @@ G.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6'}; % The transfer function from actuator forces to relative motion sensors is shown in Figure [[fig:dvf_plant_coupling]]. -freqs = logspace(1, 3, 1000); +freqs = logspace(1, 4, 1000); figure; @@ -79,19 +84,28 @@ legend([p1, p2], {'$D_{m,i}/F_i$', '$D_{m,j}/F_i$'}) linkaxes([ax1,ax2],'x'); -% Effect of the Flexible Joint stiffness on the Dynamics +% Effect of the Flexible Joint stiffness and Actuator amplification on the Dynamics % We add some stiffness and damping in the flexible joints and we re-identify the dynamics. -stewart = initializeJointDynamics(stewart); +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'}; +% We now use the amplified actuators and re-identify the dynamics + +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 new dynamics from force actuator to relative motion sensor is shown in Figure [[fig:dvf_plant_flexible_joint_decentralized]]. -freqs = logspace(1, 3, 1000); +freqs = logspace(1, 4, 1000); figure; @@ -99,6 +113,7 @@ ax1 = subplot(2, 1, 1); hold on; plot(freqs, abs(squeeze(freqresp(G( 'Dm1', 'F1'), freqs, 'Hz')))); plot(freqs, abs(squeeze(freqresp(Gf('Dm1', 'F1'), freqs, 'Hz')))); +plot(freqs, abs(squeeze(freqresp(Ga('Dm1', 'F1'), freqs, 'Hz')))); hold off; set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]); @@ -107,6 +122,7 @@ ax2 = subplot(2, 1, 2); hold on; plot(freqs, 180/pi*angle(squeeze(freqresp(G( 'Dm1', 'F1'), freqs, 'Hz'))), 'DisplayName', 'Perfect Joints'); plot(freqs, 180/pi*angle(squeeze(freqresp(Gf('Dm1', 'F1'), freqs, 'Hz'))), 'DisplayName', 'Flexible Joints'); +plot(freqs, 180/pi*angle(squeeze(freqresp(Ga('Dm1', 'F1'), freqs, 'Hz'))), 'DisplayName', 'Amplified Actuators'); hold off; set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin'); ylabel('Phase [deg]'); xlabel('Frequency [Hz]'); @@ -126,7 +142,7 @@ linkaxes([ax1,ax2],'x'); % & & s % \end{bmatrix} \] -% The root locus is shown in figure [[fig:root_locus_dvf_rot_stiffness]] and the obtained pole damping function of the control gain is shown in figure [[fig:pole_damping_gain_dvf_rot_stiffness]]. +% The root locus is shown in figure [[fig:root_locus_dvf_rot_stiffness]]. gains = logspace(0, 5, 1000); @@ -134,45 +150,27 @@ figure; hold on; plot(real(pole(G)), imag(pole(G)), 'x'); plot(real(pole(Gf)), imag(pole(Gf)), 'x'); +plot(real(pole(Ga)), imag(pole(Gf)), 'x'); set(gca,'ColorOrderIndex',1); plot(real(tzero(G)), imag(tzero(G)), 'o'); plot(real(tzero(Gf)), imag(tzero(Gf)), 'o'); +plot(real(tzero(Ga)), imag(tzero(Gf)), 'o'); for i = 1:length(gains) - cl_poles = pole(feedback(G, (gains(i)*s)*eye(6))); set(gca,'ColorOrderIndex',1); - plot(real(cl_poles), imag(cl_poles), '.'); - cl_poles = pole(feedback(Gf, (gains(i)*s)*eye(6))); + cl_poles = pole(feedback(G, (gains(i)*s)*eye(6))); + p1 = plot(real(cl_poles), imag(cl_poles), '.'); + set(gca,'ColorOrderIndex',2); - plot(real(cl_poles), imag(cl_poles), '.'); + cl_poles = pole(feedback(Gf, (gains(i)*s)*eye(6))); + p2 = plot(real(cl_poles), imag(cl_poles), '.'); + + set(gca,'ColorOrderIndex',3); + cl_poles = pole(feedback(Ga, (gains(i)*s)*eye(6))); + p3 = plot(real(cl_poles), imag(cl_poles), '.'); end -ylim([0,inf]); -xlim([-3000,0]); +ylim([0, 1.1*max(imag(pole(G)))]); +xlim([-1.1*max(imag(pole(G))),0]); xlabel('Real Part') ylabel('Imaginary Part') axis square - - - -% #+name: fig:root_locus_dvf_rot_stiffness -% #+caption: Root Locus plot with Direct Velocity Feedback when considering the Stiffness of flexible joints ([[./figs/root_locus_dvf_rot_stiffness.png][png]], [[./figs/root_locus_dvf_rot_stiffness.pdf][pdf]]) -% [[file:figs/root_locus_dvf_rot_stiffness.png]] - - -gains = logspace(0, 5, 1000); - -figure; -hold on; -for i = 1:length(gains) - set(gca,'ColorOrderIndex',1); - cl_poles = pole(feedback(G, (gains(i)*s)*eye(6))); - poles_damp = phase(cl_poles(imag(cl_poles)>0)) - pi/2; - plot(gains(i)*ones(size(poles_damp)), poles_damp, '.'); - set(gca,'ColorOrderIndex',2); - cl_poles = pole(feedback(Gf, (gains(i)*s)*eye(6))); - poles_damp = phase(cl_poles(imag(cl_poles)>0)) - pi/2; - plot(gains(i)*ones(size(poles_damp)), poles_damp, '.'); -end -xlabel('Control Gain'); -ylabel('Damping of the Poles'); -set(gca, 'XScale', 'log'); -ylim([0,pi/2]); +legend([p1, p2, p3], {'Perfect Joints', 'Flexible Joints', 'Amplified Actuator'}, 'location', 'northwest'); diff --git a/matlab/active_damping_iff.m b/matlab/active_damping_iff.m index dbfaa90..e8cb5c0 100644 --- a/matlab/active_damping_iff.m +++ b/matlab/active_damping_iff.m @@ -4,22 +4,27 @@ clear; close all; clc; %% Intialize Laplace variable s = zpk('s'); -simulinkproject('./'); +simulinkproject('../'); -open('simulink/stewart_active_damping.slx') +open('stewart_platform_model.slx') % Identification of the Dynamics with perfect Joints % We first initialize the Stewart platform without joint stiffness. -stewart = initializeFramesPositions('H', 90e-3, 'MO_B', 45e-3); +stewart = initializeStewartPlatform(); +stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3); stewart = generateGeneralConfiguration(stewart); stewart = computeJointsPose(stewart); stewart = initializeStrutDynamics(stewart); -stewart = initializeJointDynamics(stewart, 'disable', true); +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'); @@ -30,12 +35,12 @@ options = linearizeOptions; options.SampleTime = 0; %% Name of the Simulink File -mdl = 'stewart_active_damping'; +mdl = 'stewart_platform_model'; %% Input/Output definition clear io; io_i = 1; -io(io_i) = linio([mdl, '/F'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N] -io(io_i) = linio([mdl, '/Fm'], 1, 'openoutput'); io_i = io_i + 1; % Force Sensor Outputs [N] +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, options); @@ -46,7 +51,7 @@ G.OutputName = {'Fm1', 'Fm2', 'Fm3', 'Fm4', 'Fm5', 'Fm6'}; % The transfer function from actuator forces to force sensors is shown in Figure [[fig:iff_plant_coupling]]. -freqs = logspace(1, 3, 1000); +freqs = logspace(1, 4, 1000); figure; @@ -79,19 +84,28 @@ legend([p1, p2], {'$F_{m,i}/F_i$', '$F_{m,j}/F_i$'}) linkaxes([ax1,ax2],'x'); -% Effect of the Flexible Joint stiffness on the Dynamics +% Effect of the Flexible Joint stiffness and Actuator amplification on the Dynamics % We add some stiffness and damping in the flexible joints and we re-identify the dynamics. -stewart = initializeJointDynamics(stewart); +stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical'); Gf = linearize(mdl, io, options); Gf.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; Gf.OutputName = {'Fm1', 'Fm2', 'Fm3', 'Fm4', 'Fm5', 'Fm6'}; +% We now use the amplified actuators and re-identify the dynamics + +stewart = initializeAmplifiedStrutDynamics(stewart); +Ga = linearize(mdl, io, options); +Ga.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; +Ga.OutputName = {'Fm1', 'Fm2', 'Fm3', 'Fm4', 'Fm5', 'Fm6'}; + + + % The new dynamics from force actuator to force sensor is shown in Figure [[fig:iff_plant_flexible_joint_decentralized]]. -freqs = logspace(1, 3, 1000); +freqs = logspace(1, 4, 1000); figure; @@ -99,6 +113,7 @@ ax1 = subplot(2, 1, 1); hold on; plot(freqs, abs(squeeze(freqresp(G( 'Fm1', 'F1'), freqs, 'Hz')))); plot(freqs, abs(squeeze(freqresp(Gf('Fm1', 'F1'), freqs, 'Hz')))); +plot(freqs, abs(squeeze(freqresp(Ga('Fm1', 'F1'), freqs, 'Hz')))); hold off; set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); ylabel('Amplitude [N/N]'); set(gca, 'XTickLabel',[]); @@ -107,6 +122,7 @@ ax2 = subplot(2, 1, 2); hold on; plot(freqs, 180/pi*angle(squeeze(freqresp(G( 'Fm1', 'F1'), freqs, 'Hz'))), 'DisplayName', 'Perfect Joints'); plot(freqs, 180/pi*angle(squeeze(freqresp(Gf('Fm1', 'F1'), freqs, 'Hz'))), 'DisplayName', 'Flexible Joints'); +plot(freqs, 180/pi*angle(squeeze(freqresp(Ga('Fm1', 'F1'), freqs, 'Hz'))), 'DisplayName', 'Amplified Actuators'); hold off; set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin'); ylabel('Phase [deg]'); xlabel('Frequency [Hz]'); @@ -134,22 +150,30 @@ figure; hold on; plot(real(pole(G)), imag(pole(G)), 'x'); plot(real(pole(Gf)), imag(pole(Gf)), 'x'); +plot(real(pole(Ga)), imag(pole(Ga)), 'x'); set(gca,'ColorOrderIndex',1); plot(real(tzero(G)), imag(tzero(G)), 'o'); plot(real(tzero(Gf)), imag(tzero(Gf)), 'o'); +plot(real(tzero(Ga)), imag(tzero(Ga)), 'o'); for i = 1:length(gains) cl_poles = pole(feedback(G, (gains(i)/s)*eye(6))); set(gca,'ColorOrderIndex',1); - plot(real(cl_poles), imag(cl_poles), '.'); + p1 = plot(real(cl_poles), imag(cl_poles), '.'); + cl_poles = pole(feedback(Gf, (gains(i)/s)*eye(6))); set(gca,'ColorOrderIndex',2); - plot(real(cl_poles), imag(cl_poles), '.'); + p2 = plot(real(cl_poles), imag(cl_poles), '.'); + + cl_poles = pole(feedback(Ga, (gains(i)/s)*eye(6))); + set(gca,'ColorOrderIndex',3); + p3 = plot(real(cl_poles), imag(cl_poles), '.'); end -ylim([0,inf]); -xlim([-3000,0]); +ylim([0, 1.1*max(imag(pole(G)))]); +xlim([-1.1*max(imag(pole(G))),0]); xlabel('Real Part') ylabel('Imaginary Part') axis square +legend([p1, p2, p3], {'Perfect Joints', 'Flexible Joints', 'Amplified Actuator'}, 'location', 'northwest'); @@ -166,13 +190,20 @@ for i = 1:length(gains) set(gca,'ColorOrderIndex',1); cl_poles = pole(feedback(G, (gains(i)/s)*eye(6))); poles_damp = phase(cl_poles(imag(cl_poles)>0)) - pi/2; - plot(gains(i)*ones(size(poles_damp)), poles_damp, '.'); + p1 = plot(gains(i)*ones(size(poles_damp)), poles_damp, '.'); + set(gca,'ColorOrderIndex',2); cl_poles = pole(feedback(Gf, (gains(i)/s)*eye(6))); poles_damp = phase(cl_poles(imag(cl_poles)>0)) - pi/2; - plot(gains(i)*ones(size(poles_damp)), poles_damp, '.'); + p2 = plot(gains(i)*ones(size(poles_damp)), poles_damp, '.'); + + set(gca,'ColorOrderIndex',3); + cl_poles = pole(feedback(Ga, (gains(i)/s)*eye(6))); + poles_damp = phase(cl_poles(imag(cl_poles)>0)) - pi/2; + p3 = plot(gains(i)*ones(size(poles_damp)), poles_damp, '.'); end xlabel('Control Gain'); ylabel('Damping of the Poles'); set(gca, 'XScale', 'log'); ylim([0,pi/2]); +legend([p1, p2, p3], {'Perfect Joints', 'Flexible Joints', 'Amplified Actuator'}, 'location', 'northwest'); diff --git a/matlab/active_damping_inertial.m b/matlab/active_damping_inertial.m index 9d6f03f..1816852 100644 --- a/matlab/active_damping_inertial.m +++ b/matlab/active_damping_inertial.m @@ -4,33 +4,38 @@ clear; close all; clc; %% Intialize Laplace variable s = zpk('s'); -simulinkproject('./'); +simulinkproject('../'); -open('simulink/stewart_active_damping.slx') +open('stewart_platform_model.slx') % Identification of the Dynamics -stewart = initializeFramesPositions('H', 90e-3, 'MO_B', 45e-3); +stewart = initializeStewartPlatform(); +stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3); stewart = generateGeneralConfiguration(stewart); stewart = computeJointsPose(stewart); stewart = initializeStrutDynamics(stewart); -stewart = initializeJointDynamics(stewart, 'disable', true); +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', 'none'); %% Options for Linearized options = linearizeOptions; options.SampleTime = 0; %% Name of the Simulink File -mdl = 'stewart_active_damping'; +mdl = 'stewart_platform_model'; %% Input/Output definition clear io; io_i = 1; -io(io_i) = linio([mdl, '/F'], 1, 'openinput'); io_i = io_i + 1; % Actuator Force Inputs [N] -io(io_i) = linio([mdl, '/Vm'], 1, 'openoutput'); io_i = io_i + 1; % Absolute velocity of each leg [m/s] +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); @@ -41,7 +46,7 @@ G.OutputName = {'Vm1', 'Vm2', 'Vm3', 'Vm4', 'Vm5', 'Vm6'}; % The transfer function from actuator forces to force sensors is shown in Figure [[fig:inertial_plant_coupling]]. -freqs = logspace(1, 3, 1000); +freqs = logspace(1, 4, 1000); figure; @@ -74,19 +79,28 @@ legend([p1, p2], {'$F_{m,i}/F_i$', '$F_{m,j}/F_i$'}) linkaxes([ax1,ax2],'x'); -% Effect of the Flexible Joint stiffness on the Dynamics +% Effect of the Flexible Joint stiffness and Actuator amplification on the Dynamics % We add some stiffness and damping in the flexible joints and we re-identify the dynamics. -stewart = initializeJointDynamics(stewart); +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'}; +% We now use the amplified actuators and re-identify the dynamics + +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 new dynamics from force actuator to force sensor is shown in Figure [[fig:inertial_plant_flexible_joint_decentralized]]. -freqs = logspace(1, 3, 1000); +freqs = logspace(1, 4, 1000); figure; @@ -94,6 +108,7 @@ ax1 = subplot(2, 1, 1); hold on; plot(freqs, abs(squeeze(freqresp(G( 'Vm1', 'F1'), freqs, 'Hz')))); plot(freqs, abs(squeeze(freqresp(Gf('Vm1', 'F1'), freqs, 'Hz')))); +plot(freqs, abs(squeeze(freqresp(Ga('Vm1', 'F1'), freqs, 'Hz')))); hold off; set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); ylabel('Amplitude [$\frac{m/s}{N}$]'); set(gca, 'XTickLabel',[]); @@ -102,6 +117,7 @@ ax2 = subplot(2, 1, 2); hold on; plot(freqs, 180/pi*angle(squeeze(freqresp(G( 'Vm1', 'F1'), freqs, 'Hz'))), 'DisplayName', 'Perfect Joints'); plot(freqs, 180/pi*angle(squeeze(freqresp(Gf('Vm1', 'F1'), freqs, 'Hz'))), 'DisplayName', 'Flexible Joints'); +plot(freqs, 180/pi*angle(squeeze(freqresp(Ga('Vm1', 'F1'), freqs, 'Hz'))), 'DisplayName', 'Amplified Actuator'); hold off; set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin'); ylabel('Phase [deg]'); xlabel('Frequency [Hz]'); @@ -121,53 +137,35 @@ linkaxes([ax1,ax2],'x'); % 0 & & 1 % \end{bmatrix} \] -% The root locus is shown in figure [[fig:root_locus_inertial_rot_stiffness]] and the obtained pole damping function of the control gain is shown in figure [[fig:pole_damping_gain_inertial_rot_stiffness]]. +% The root locus is shown in figure [[fig:root_locus_inertial_rot_stiffness]]. -gains = logspace(0, 5, 1000); +gains = logspace(2, 5, 100); figure; hold on; plot(real(pole(G)), imag(pole(G)), 'x'); plot(real(pole(Gf)), imag(pole(Gf)), 'x'); +plot(real(pole(Ga)), imag(pole(Ga)), 'x'); set(gca,'ColorOrderIndex',1); plot(real(tzero(G)), imag(tzero(G)), 'o'); plot(real(tzero(Gf)), imag(tzero(Gf)), 'o'); +plot(real(tzero(Ga)), imag(tzero(Ga)), 'o'); for i = 1:length(gains) - cl_poles = pole(feedback(G, gains(i)*eye(6))); set(gca,'ColorOrderIndex',1); - plot(real(cl_poles), imag(cl_poles), '.'); - cl_poles = pole(feedback(Gf, gains(i)*eye(6))); + cl_poles = pole(feedback(G, gains(i)*eye(6))); + p1 = plot(real(cl_poles), imag(cl_poles), '.'); + set(gca,'ColorOrderIndex',2); - plot(real(cl_poles), imag(cl_poles), '.'); + cl_poles = pole(feedback(Gf, gains(i)*eye(6))); + p2 = plot(real(cl_poles), imag(cl_poles), '.'); + + set(gca,'ColorOrderIndex',3); + cl_poles = pole(feedback(Ga, gains(i)*eye(6))); + p3 = plot(real(cl_poles), imag(cl_poles), '.'); end -ylim([0,2000]); -xlim([-2000,0]); +ylim([0, 3*max(imag(pole(G)))]); +xlim([-3*max(imag(pole(G))),0]); xlabel('Real Part') ylabel('Imaginary Part') axis square - - - -% #+name: fig:root_locus_inertial_rot_stiffness -% #+caption: Root Locus plot with Decentralized Inertial Control when considering the stiffness of flexible joints ([[./figs/root_locus_inertial_rot_stiffness.png][png]], [[./figs/root_locus_inertial_rot_stiffness.pdf][pdf]]) -% [[file:figs/root_locus_inertial_rot_stiffness.png]] - - -gains = logspace(0, 5, 1000); - -figure; -hold on; -for i = 1:length(gains) - set(gca,'ColorOrderIndex',1); - cl_poles = pole(feedback(G, gains(i)*eye(6))); - poles_damp = phase(cl_poles(imag(cl_poles)>0)) - pi/2; - plot(gains(i)*ones(size(poles_damp)), poles_damp, '.'); - set(gca,'ColorOrderIndex',2); - cl_poles = pole(feedback(Gf, gains(i)*eye(6))); - poles_damp = phase(cl_poles(imag(cl_poles)>0)) - pi/2; - plot(gains(i)*ones(size(poles_damp)), poles_damp, '.'); -end -xlabel('Control Gain'); -ylabel('Damping of the Poles'); -set(gca, 'XScale', 'log'); -ylim([0,pi/2]); +legend([p1, p2, p3], {'Perfect Joints', 'Flexible Joints', 'Amplified Actuator'}, 'location', 'northwest'); diff --git a/matlab/cubic_conf_above_platforml.m b/matlab/cubic_conf_above_platforml.m new file mode 100644 index 0000000..c19eb45 --- /dev/null +++ b/matlab/cubic_conf_above_platforml.m @@ -0,0 +1,93 @@ +%% Clear Workspace and Close figures +clear; close all; clc; + +%% Intialize Laplace variable +s = zpk('s'); + +simulinkproject('../'); + +% Having Cube's center above the top platform +% Let's say we want to have a diagonal stiffness matrix when $\{A\}$ and $\{B\}$ are located above the top platform. +% Thus, we want the cube's center to be located above the top center. + +% Let's fix the Height of the Stewart platform and the position of frames $\{A\}$ and $\{B\}$: + +H = 100e-3; % height of the Stewart platform [m] +MO_B = 20e-3; % Position {B} with respect to {M} [m] + + + +% We find the several Cubic configuration for the Stewart platform where the center of the cube is located at frame $\{A\}$. +% The differences between the configuration are the cube's size: +% - Small Cube Size in Figure [[fig:stewart_cubic_conf_type_1]] +% - Medium Cube Size in Figure [[fig:stewart_cubic_conf_type_2]] +% - Large Cube Size in Figure [[fig:stewart_cubic_conf_type_3]] + +% For each of the configuration, the Stiffness matrix is diagonal with $k_x = k_y = k_y = 2k$ with $k$ is the stiffness of each strut. +% However, the rotational stiffnesses are increasing with the cube's size but the required size of the platform is also increasing, so there is a trade-off here. + + +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} + +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', 1.2*max(vecnorm(stewart.platform_F.Fa)), 'Mpr', 1.2*max(vecnorm(stewart.platform_M.Mb))); +displayArchitecture(stewart, 'labels', false); +scatter3(0, 0, FOc, 200, 'kh'); + + + +% #+name: tab:stewart_cubic_conf_type_1 +% #+caption: Stiffness Matrix +% #+RESULTS: +% | 2 | 0 | -2.8e-16 | 0 | 2.4e-17 | 0 | +% | 0 | 2 | 0 | -2.3e-17 | 0 | 0 | +% | -2.8e-16 | 0 | 2 | -2.1e-19 | 0 | 0 | +% | 0 | -2.3e-17 | -2.1e-19 | 0.0024 | -5.4e-20 | 6.5e-19 | +% | 2.4e-17 | 0 | 4.9e-19 | -2.3e-20 | 0.0024 | 0 | +% | -1.2e-18 | 1.1e-18 | 0 | 6.2e-19 | 0 | 0.0096 | + + +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} + +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', 1.2*max(vecnorm(stewart.platform_F.Fa)), 'Mpr', 1.2*max(vecnorm(stewart.platform_M.Mb))); +displayArchitecture(stewart, 'labels', false); +scatter3(0, 0, FOc, 200, 'kh'); + + + +% #+name: tab:stewart_cubic_conf_type_2 +% #+caption: Stiffness Matrix +% #+RESULTS: +% | 2 | 0 | -1.9e-16 | 0 | 5.6e-17 | 0 | +% | 0 | 2 | 0 | -7.6e-17 | 0 | 0 | +% | -1.9e-16 | 0 | 2 | 2.5e-18 | 2.8e-17 | 0 | +% | 0 | -7.6e-17 | 2.5e-18 | 0.034 | 8.7e-19 | 8.7e-18 | +% | 5.7e-17 | 0 | 3.2e-17 | 2.9e-19 | 0.034 | 0 | +% | -1e-18 | -1.3e-17 | 5.6e-17 | 8.4e-18 | 0 | 0.14 | + + +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', 0, 'MHb', 0); +stewart = computeJointsPose(stewart); +stewart = initializeStrutDynamics(stewart, 'K', ones(6,1)); +stewart = computeJacobian(stewart); +stewart = initializeCylindricalPlatforms(stewart, 'Fpr', 1.2*max(vecnorm(stewart.platform_F.Fa)), 'Mpr', 1.2*max(vecnorm(stewart.platform_M.Mb))); +displayArchitecture(stewart, 'labels', false); +scatter3(0, 0, FOc, 200, 'kh'); diff --git a/matlab/cubic_conf_coupling_cartesianl.m b/matlab/cubic_conf_coupling_cartesianl.m new file mode 100644 index 0000000..711cb10 --- /dev/null +++ b/matlab/cubic_conf_coupling_cartesianl.m @@ -0,0 +1,336 @@ +%% Clear Workspace and Close figures +clear; close all; clc; + +%% Intialize Laplace variable +s = zpk('s'); + +simulinkproject('../'); + +% Cube's center at the Center of Mass of the mobile platform +% Let's create a Cubic Stewart Platform where the *Center of Mass of the mobile platform is located at the center of the cube*. + +% We define the size of the Stewart platform and the position of frames $\{A\}$ and $\{B\}$. + +H = 200e-3; % height of the Stewart platform [m] +MO_B = -10e-3; % Position {B} with respect to {M} [m] + + + +% Now, we set the cube's parameters such that the center of the cube is coincident with $\{A\}$ and $\{B\}$. + +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); + + + +% Now we set the geometry and mass of the mobile platform such that its center of mass is coincident with $\{A\}$ and $\{B\}$. + +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))); + + + +% And we set small mass for the struts. + +stewart = initializeCylindricalStruts(stewart, 'Fsm', 1e-3, 'Msm', 1e-3); +stewart = initializeInertialSensor(stewart); + + + +% No flexibility below the Stewart platform and no payload. + +ground = initializeGround('type', 'none'); +payload = initializePayload('type', 'none'); + + + +% The obtain geometry is shown in figure [[fig:stewart_cubic_conf_decouple_dynamics]]. + + +displayArchitecture(stewart, 'labels', false, 'view', 'all'); + + + +% #+name: fig:stewart_cubic_conf_decouple_dynamics +% #+caption: Geometry used for the simulations - The cube's center, the frames $\{A\}$ and $\{B\}$ and the Center of mass of the mobile platform are coincident ([[./figs/stewart_cubic_conf_decouple_dynamics.png][png]], [[./figs/stewart_cubic_conf_decouple_dynamics.pdf][pdf]]) +% [[file:figs/stewart_cubic_conf_decouple_dynamics.png]] + +% We now identify the dynamics from forces applied in each strut $\bm{\tau}$ to the displacement of each strut $d \bm{\mathcal{L}}$. + +open('stewart_platform_model.slx') + +%% Options for Linearized +options = linearizeOptions; +options.SampleTime = 0; + +%% 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] + +%% Run the linearization +G = linearize(mdl, io, options); +G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; +G.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6'}; + + + +% Now, thanks to the Jacobian (Figure [[fig:local_to_cartesian_coordinates]]), we compute the transfer function from $\bm{\mathcal{F}}$ to $\bm{\mathcal{X}}$. + +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'}; + + + +% The obtain dynamics $\bm{G}_{c}(s) = \bm{J}^{-T} \bm{G}(s) \bm{J}^{-1}$ is shown in Figure [[fig:stewart_cubic_decoupled_dynamics_cartesian]]. + + +freqs = logspace(1, 3, 500); + +figure; + +ax1 = subplot(2, 2, 1); +hold on; +for i = 1:6 + for j = i+1:6 + plot(freqs, abs(squeeze(freqresp(Gc(i, j), freqs, 'Hz'))), 'k-'); + end +end +set(gca,'ColorOrderIndex',1); +plot(freqs, abs(squeeze(freqresp(Gc(1, 1), freqs, 'Hz')))); +plot(freqs, abs(squeeze(freqresp(Gc(2, 2), freqs, 'Hz')))); +plot(freqs, abs(squeeze(freqresp(Gc(3, 3), freqs, 'Hz')))); +hold off; +set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); +ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]); + +ax3 = subplot(2, 2, 3); +hold on; +for i = 1:6 + for j = i+1:6 + p4 = plot(freqs, 180/pi*angle(squeeze(freqresp(Gc(i, j), freqs, 'Hz'))), 'k-'); + end +end +set(gca,'ColorOrderIndex',1); +p1 = plot(freqs, 180/pi*angle(squeeze(freqresp(Gc(1, 1), freqs, 'Hz')))); +p2 = plot(freqs, 180/pi*angle(squeeze(freqresp(Gc(2, 2), freqs, 'Hz')))); +p3 = plot(freqs, 180/pi*angle(squeeze(freqresp(Gc(3, 3), freqs, 'Hz')))); +hold off; +set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin'); +ylabel('Phase [deg]'); xlabel('Frequency [Hz]'); +ylim([-180, 180]); +yticks([-180, -90, 0, 90, 180]); +legend([p1, p2, p3, p4], {'$D_x/F_x$','$D_y/F_y$', '$D_z/F_z$', '$D_i/F_j$'}) + +ax2 = subplot(2, 2, 2); +hold on; +for i = 1:6 + for j = i+1:6 + plot(freqs, abs(squeeze(freqresp(Gc(i, j), freqs, 'Hz'))), 'k-'); + end +end +set(gca,'ColorOrderIndex',1); +plot(freqs, abs(squeeze(freqresp(Gc(4, 4), freqs, 'Hz')))); +plot(freqs, abs(squeeze(freqresp(Gc(5, 5), freqs, 'Hz')))); +plot(freqs, abs(squeeze(freqresp(Gc(6, 6), freqs, 'Hz')))); +hold off; +set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); +ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]); + +ax4 = subplot(2, 2, 4); +hold on; +for i = 1:6 + for j = i+1:6 + p4 = plot(freqs, 180/pi*angle(squeeze(freqresp(Gc(i, j), freqs, 'Hz'))), 'k-'); + end +end +set(gca,'ColorOrderIndex',1); +p1 = plot(freqs, 180/pi*angle(squeeze(freqresp(Gc(4, 4), freqs, 'Hz')))); +p2 = plot(freqs, 180/pi*angle(squeeze(freqresp(Gc(5, 5), freqs, 'Hz')))); +p3 = plot(freqs, 180/pi*angle(squeeze(freqresp(Gc(6, 6), freqs, 'Hz')))); +hold off; +set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin'); +ylabel('Phase [deg]'); xlabel('Frequency [Hz]'); +ylim([-180, 180]); +yticks([-180, -90, 0, 90, 180]); +legend([p1, p2, p3, p4], {'$R_x/M_x$','$R_y/M_y$', '$R_z/M_z$', '$R_i/M_j$'}) + +linkaxes([ax1,ax2,ax3,ax4],'x'); + +% Cube's center not coincident with the Mass of the Mobile platform +% Let's create a Stewart platform with a cubic architecture where the cube's center is at the center of the Stewart platform. + +H = 200e-3; % height of the Stewart platform [m] +MO_B = -100e-3; % Position {B} with respect to {M} [m] + + + +% Now, we set the cube's parameters such that the center of the cube is coincident with $\{A\}$ and $\{B\}$. + +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); + + + +% However, the Center of Mass of the mobile platform is *not* located at the cube's center. + +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))); + + + +% And we set small mass for the struts. + +stewart = initializeCylindricalStruts(stewart, 'Fsm', 1e-3, 'Msm', 1e-3); +stewart = initializeInertialSensor(stewart); + + + +% No flexibility below the Stewart platform and no payload. + +ground = initializeGround('type', 'none'); +payload = initializePayload('type', 'none'); + + + +% The obtain geometry is shown in figure [[fig:stewart_cubic_conf_mass_above]]. + +displayArchitecture(stewart, 'labels', false, 'view', 'all'); + + + +% #+name: fig:stewart_cubic_conf_mass_above +% #+caption: Geometry used for the simulations - The cube's center is coincident with the frames $\{A\}$ and $\{B\}$ but not with the Center of mass of the mobile platform ([[./figs/stewart_cubic_conf_mass_above.png][png]], [[./figs/stewart_cubic_conf_mass_above.pdf][pdf]]) +% [[file:figs/stewart_cubic_conf_mass_above.png]] + +% We now identify the dynamics from forces applied in each strut $\bm{\tau}$ to the displacement of each strut $d \bm{\mathcal{L}}$. + +open('stewart_platform_model.slx') + +%% Options for Linearized +options = linearizeOptions; +options.SampleTime = 0; + +%% 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] + +%% Run the linearization +G = linearize(mdl, io, options); +G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; +G.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6'}; + + + +% And we use the Jacobian to compute the transfer function from $\bm{\mathcal{F}}$ to $\bm{\mathcal{X}}$. + +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'}; + + + +% The obtain dynamics $\bm{G}_{c}(s) = \bm{J}^{-T} \bm{G}(s) \bm{J}^{-1}$ is shown in Figure [[fig:stewart_conf_coupling_mass_matrix]]. + + +freqs = logspace(1, 3, 500); + +figure; + +ax1 = subplot(2, 2, 1); +hold on; +for i = 1:6 + for j = i+1:6 + plot(freqs, abs(squeeze(freqresp(Gc(i, j), freqs, 'Hz'))), 'k-'); + end +end +set(gca,'ColorOrderIndex',1); +plot(freqs, abs(squeeze(freqresp(Gc(1, 1), freqs, 'Hz')))); +plot(freqs, abs(squeeze(freqresp(Gc(2, 2), freqs, 'Hz')))); +plot(freqs, abs(squeeze(freqresp(Gc(3, 3), freqs, 'Hz')))); +hold off; +set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); +ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]); + +ax3 = subplot(2, 2, 3); +hold on; +for i = 1:6 + for j = i+1:6 + p4 = plot(freqs, 180/pi*angle(squeeze(freqresp(Gc(i, j), freqs, 'Hz'))), 'k-'); + end +end +set(gca,'ColorOrderIndex',1); +p1 = plot(freqs, 180/pi*angle(squeeze(freqresp(Gc(1, 1), freqs, 'Hz')))); +p2 = plot(freqs, 180/pi*angle(squeeze(freqresp(Gc(2, 2), freqs, 'Hz')))); +p3 = plot(freqs, 180/pi*angle(squeeze(freqresp(Gc(3, 3), freqs, 'Hz')))); +hold off; +set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin'); +ylabel('Phase [deg]'); xlabel('Frequency [Hz]'); +ylim([-180, 180]); +yticks([-180, -90, 0, 90, 180]); +legend([p1, p2, p3, p4], {'$D_x/F_x$','$D_y/F_y$', '$D_z/F_z$', '$D_i/F_j$'}) + +ax2 = subplot(2, 2, 2); +hold on; +for i = 1:6 + for j = i+1:6 + plot(freqs, abs(squeeze(freqresp(Gc(i, j), freqs, 'Hz'))), 'k-'); + end +end +set(gca,'ColorOrderIndex',1); +plot(freqs, abs(squeeze(freqresp(Gc(4, 4), freqs, 'Hz')))); +plot(freqs, abs(squeeze(freqresp(Gc(5, 5), freqs, 'Hz')))); +plot(freqs, abs(squeeze(freqresp(Gc(6, 6), freqs, 'Hz')))); +hold off; +set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); +ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]); + +ax4 = subplot(2, 2, 4); +hold on; +for i = 1:6 + for j = i+1:6 + p4 = plot(freqs, 180/pi*angle(squeeze(freqresp(Gc(i, j), freqs, 'Hz'))), 'k-'); + end +end +set(gca,'ColorOrderIndex',1); +p1 = plot(freqs, 180/pi*angle(squeeze(freqresp(Gc(4, 4), freqs, 'Hz')))); +p2 = plot(freqs, 180/pi*angle(squeeze(freqresp(Gc(5, 5), freqs, 'Hz')))); +p3 = plot(freqs, 180/pi*angle(squeeze(freqresp(Gc(6, 6), freqs, 'Hz')))); +hold off; +set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin'); +ylabel('Phase [deg]'); xlabel('Frequency [Hz]'); +ylim([-180, 180]); +yticks([-180, -90, 0, 90, 180]); +legend([p1, p2, p3, p4], {'$R_x/M_x$','$R_y/M_y$', '$R_z/M_z$', '$R_i/M_j$'}) + +linkaxes([ax1,ax2,ax3,ax4],'x'); diff --git a/matlab/cubic_conf_coupling_strutsl.m b/matlab/cubic_conf_coupling_strutsl.m new file mode 100644 index 0000000..5e39c72 --- /dev/null +++ b/matlab/cubic_conf_coupling_strutsl.m @@ -0,0 +1,301 @@ +%% Clear Workspace and Close figures +clear; close all; clc; + +%% Intialize Laplace variable +s = zpk('s'); + +simulinkproject('../'); + +% Coupling between the actuators and sensors - Cubic Architecture +% Let's generate a Cubic architecture where the cube's center and the frames $\{A\}$ and $\{B\}$ are coincident. + + +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); + + + +% No flexibility below the Stewart platform and no payload. + +ground = initializeGround('type', 'none'); +payload = initializePayload('type', 'none'); + +displayArchitecture(stewart, 'labels', false, 'view', 'all'); + + + +% #+name: fig:stewart_architecture_coupling_struts_cubic +% #+caption: Geometry of the generated Stewart platform ([[./figs/stewart_architecture_coupling_struts_cubic.png][png]], [[./figs/stewart_architecture_coupling_struts_cubic.pdf][pdf]]) +% [[file:figs/stewart_architecture_coupling_struts_cubic.png]] + +% And we identify the dynamics from the actuator forces $\tau_{i}$ to the relative motion sensors $\delta \mathcal{L}_{i}$ (Figure [[fig:coupling_struts_relative_sensor_cubic]]) and to the force sensors $\tau_{m,i}$ (Figure [[fig:coupling_struts_force_sensor_cubic]]). + + +open('stewart_platform_model.slx') + +%% Options for Linearized +options = linearizeOptions; +options.SampleTime = 0; + +%% 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] + +%% Run the linearization +G = linearize(mdl, io, options); +G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; +G.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6'}; + +freqs = logspace(1, 3, 1000); + +figure; + +ax1 = subplot(2, 1, 1); +hold on; +for i = 1:6 + for j = i+1:6 + plot(freqs, abs(squeeze(freqresp(G(i, j), freqs, 'Hz'))), 'k-'); + end +end +set(gca,'ColorOrderIndex',1); +plot(freqs, abs(squeeze(freqresp(G(1, 1), freqs, 'Hz')))); +hold off; +set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); +ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]); + +ax3 = subplot(2, 1, 2); +hold on; +for i = 1:6 + for j = i+1:6 + p2 = plot(freqs, 180/pi*angle(squeeze(freqresp(G(i, j), freqs, 'Hz'))), 'k-'); + end +end +set(gca,'ColorOrderIndex',1); +p1 = plot(freqs, 180/pi*angle(squeeze(freqresp(G(1, 1), freqs, 'Hz')))); +hold off; +set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin'); +ylabel('Phase [deg]'); xlabel('Frequency [Hz]'); +ylim([-180, 180]); +yticks([-180, -90, 0, 90, 180]); +legend([p1, p2], {'$L_i/\tau_i$', '$L_i/\tau_j$'}) + +linkaxes([ax1,ax2],'x'); + + + +% #+name: fig:coupling_struts_relative_sensor_cubic +% #+caption: Dynamics from the force actuators to the relative motion sensors ([[./figs/coupling_struts_relative_sensor_cubic.png][png]], [[./figs/coupling_struts_relative_sensor_cubic.pdf][pdf]]) +% [[file:figs/coupling_struts_relative_sensor_cubic.png]] + + +%% 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, options); +G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; +G.OutputName = {'Fm1', 'Fm2', 'Fm3', 'Fm4', 'Fm5', 'Fm6'}; + +freqs = logspace(1, 3, 500); + +figure; + +ax1 = subplot(2, 1, 1); +hold on; +for i = 1:6 + for j = i+1:6 + plot(freqs, abs(squeeze(freqresp(G(i, j), freqs, 'Hz'))), 'k-'); + end +end +set(gca,'ColorOrderIndex',1); +plot(freqs, abs(squeeze(freqresp(G(1, 1), freqs, 'Hz')))); +hold off; +set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); +ylabel('Amplitude [N/N]'); set(gca, 'XTickLabel',[]); + +ax3 = subplot(2, 1, 2); +hold on; +for i = 1:6 + for j = i+1:6 + p2 = plot(freqs, 180/pi*angle(squeeze(freqresp(G(i, j), freqs, 'Hz'))), 'k-'); + end +end +set(gca,'ColorOrderIndex',1); +p1 = plot(freqs, 180/pi*angle(squeeze(freqresp(G(1, 1), freqs, 'Hz')))); +hold off; +set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin'); +ylabel('Phase [deg]'); xlabel('Frequency [Hz]'); +ylim([-180, 180]); +yticks([-180, -90, 0, 90, 180]); +legend([p1, p2], {'$F_{m,i}/\tau_i$', '$F_{m,i}/\tau_j$'}) + +linkaxes([ax1,ax2],'x'); + +% Coupling between the actuators and sensors - Non-Cubic Architecture +% Now we generate a Stewart platform which is not cubic but with approximately the same size as the previous cubic architecture. + + +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); + + + +% No flexibility below the Stewart platform and no payload. + +ground = initializeGround('type', 'none'); +payload = initializePayload('type', 'none'); + +displayArchitecture(stewart, 'labels', false, 'view', 'all'); + + + +% #+name: fig:stewart_architecture_coupling_struts_non_cubic +% #+caption: Geometry of the generated Stewart platform ([[./figs/stewart_architecture_coupling_struts_non_cubic.png][png]], [[./figs/stewart_architecture_coupling_struts_non_cubic.pdf][pdf]]) +% [[file:figs/stewart_architecture_coupling_struts_non_cubic.png]] + +% And we identify the dynamics from the actuator forces $\tau_{i}$ to the relative motion sensors $\delta \mathcal{L}_{i}$ (Figure [[fig:coupling_struts_relative_sensor_non_cubic]]) and to the force sensors $\tau_{m,i}$ (Figure [[fig:coupling_struts_force_sensor_non_cubic]]). + + +open('stewart_platform_model.slx') + +%% Options for Linearized +options = linearizeOptions; +options.SampleTime = 0; + +%% 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] + +%% Run the linearization +G = linearize(mdl, io, options); +G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; +G.OutputName = {'Dm1', 'Dm2', 'Dm3', 'Dm4', 'Dm5', 'Dm6'}; + +freqs = logspace(1, 3, 1000); + +figure; + +ax1 = subplot(2, 1, 1); +hold on; +for i = 1:6 + for j = i+1:6 + plot(freqs, abs(squeeze(freqresp(G(i, j), freqs, 'Hz'))), 'k-'); + end +end +set(gca,'ColorOrderIndex',1); +plot(freqs, abs(squeeze(freqresp(G(1, 1), freqs, 'Hz')))); +hold off; +set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); +ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]); + +ax3 = subplot(2, 1, 2); +hold on; +for i = 1:6 + for j = i+1:6 + p2 = plot(freqs, 180/pi*angle(squeeze(freqresp(G(i, j), freqs, 'Hz'))), 'k-'); + end +end +set(gca,'ColorOrderIndex',1); +p1 = plot(freqs, 180/pi*angle(squeeze(freqresp(G(1, 1), freqs, 'Hz')))); +hold off; +set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin'); +ylabel('Phase [deg]'); xlabel('Frequency [Hz]'); +ylim([-180, 180]); +yticks([-180, -90, 0, 90, 180]); +legend([p1, p2], {'$L_i/\tau_i$', '$L_i/\tau_j$'}) + +linkaxes([ax1,ax2],'x'); + + + +% #+name: fig:coupling_struts_relative_sensor_non_cubic +% #+caption: Dynamics from the force actuators to the relative motion sensors ([[./figs/coupling_struts_relative_sensor_non_cubic.png][png]], [[./figs/coupling_struts_relative_sensor_non_cubic.pdf][pdf]]) +% [[file:figs/coupling_struts_relative_sensor_non_cubic.png]] + + +%% 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, options); +G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; +G.OutputName = {'Fm1', 'Fm2', 'Fm3', 'Fm4', 'Fm5', 'Fm6'}; + +freqs = logspace(1, 3, 500); + +figure; + +ax1 = subplot(2, 1, 1); +hold on; +for i = 1:6 + for j = i+1:6 + plot(freqs, abs(squeeze(freqresp(G(i, j), freqs, 'Hz'))), 'k-'); + end +end +set(gca,'ColorOrderIndex',1); +plot(freqs, abs(squeeze(freqresp(G(1, 1), freqs, 'Hz')))); +hold off; +set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); +ylabel('Amplitude [N/N]'); set(gca, 'XTickLabel',[]); + +ax3 = subplot(2, 1, 2); +hold on; +for i = 1:6 + for j = i+1:6 + p2 = plot(freqs, 180/pi*angle(squeeze(freqresp(G(i, j), freqs, 'Hz'))), 'k-'); + end +end +set(gca,'ColorOrderIndex',1); +p1 = plot(freqs, 180/pi*angle(squeeze(freqresp(G(1, 1), freqs, 'Hz')))); +hold off; +set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin'); +ylabel('Phase [deg]'); xlabel('Frequency [Hz]'); +ylim([-180, 180]); +yticks([-180, -90, 0, 90, 180]); +legend([p1, p2], {'$F_{m,i}/\tau_i$', '$F_{m,i}/\tau_j$'}) + +linkaxes([ax1,ax2],'x'); diff --git a/matlab/cubic_conf_size_analysisl.m b/matlab/cubic_conf_size_analysisl.m new file mode 100644 index 0000000..5ada068 --- /dev/null +++ b/matlab/cubic_conf_size_analysisl.m @@ -0,0 +1,51 @@ +%% Clear Workspace and Close figures +clear; close all; clc; + +%% Intialize Laplace variable +s = zpk('s'); + +simulinkproject('../'); + +% Analysis +% We initialize the wanted cube's size. + +Hcs = 1e-3*[250:20:350]; % Heights for the Cube [m] +Ks = zeros(6, 6, length(Hcs)); + + + +% The height of the Stewart platform is fixed: + +H = 100e-3; % height of the Stewart platform [m] + + + +% The frames $\{A\}$ and $\{B\}$ are positioned at the Stewart platform center as well as the cube's center: + +MO_B = -50e-3; % Position {B} with respect to {M} [m] +FOc = H + MO_B; % Center of the cube with respect to {F} + +stewart = initializeStewartPlatform(); +stewart = initializeFramesPositions(stewart, 'H', H, 'MO_B', MO_B); +for i = 1:length(Hcs) + Hc = Hcs(i); + stewart = generateCubicConfiguration(stewart, 'Hc', Hc, 'FOc', FOc, 'FHa', 0, 'MHb', 0); + stewart = computeJointsPose(stewart); + stewart = initializeStrutDynamics(stewart, 'K', ones(6,1)); + stewart = computeJacobian(stewart); + Ks(:,:,i) = stewart.kinematics.K; +end + + + +% We find that for all the cube's size, $k_x = k_y = k_z = k$ where $k$ is the strut stiffness. +% We also find that $k_{\theta_x} = k_{\theta_y}$ and $k_{\theta_z}$ are varying with the cube's size (figure [[fig:stiffness_cube_size]]). + + +figure; +hold on; +plot(Hcs, squeeze(Ks(4, 4, :)), 'DisplayName', '$k_{\theta_x} = k_{\theta_y}$'); +plot(Hcs, squeeze(Ks(6, 6, :)), 'DisplayName', '$k_{\theta_z}$'); +hold off; +legend('location', 'northwest'); +xlabel('Cube Size [m]'); ylabel('Rotational stiffnes [normalized]'); diff --git a/matlab/cubic_conf_stiffnessl.m b/matlab/cubic_conf_stiffnessl.m new file mode 100644 index 0000000..8253ca4 --- /dev/null +++ b/matlab/cubic_conf_stiffnessl.m @@ -0,0 +1,96 @@ +%% Clear Workspace and Close figures +clear; close all; clc; + +%% Intialize Laplace variable +s = zpk('s'); + +simulinkproject('../'); + +% Cubic Stewart platform centered with the cube center - Jacobian estimated at the cube center +% We create a cubic Stewart platform (figure [[fig:cubic_conf_centered_J_center]]) in such a way that the center of the cube (black star) is located at the center of the Stewart platform (blue dot). +% The Jacobian matrix is estimated at the location of the center of the cube. + + +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); + +displayArchitecture(stewart, 'labels', false); +scatter3(0, 0, FOc, 200, 'kh'); + +% Cubic Stewart platform centered with the cube center - Jacobian not estimated at the cube center +% We create a cubic Stewart platform with center of the cube located at the center of the Stewart platform (figure [[fig:cubic_conf_centered_J_not_center]]). +% The Jacobian matrix is not estimated at the location of the center of the cube. + + +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); + +displayArchitecture(stewart, 'labels', false); +scatter3(0, 0, FOc, 200, 'kh'); + +% Cubic Stewart platform not centered with the cube center - Jacobian estimated at the cube center +% Here, the "center" of the Stewart platform is not at the cube center (figure [[fig:cubic_conf_not_centered_J_center]]). +% The Jacobian is estimated at the cube center. + + +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); + +displayArchitecture(stewart, 'labels', false); +scatter3(0, 0, FOc, 200, 'kh'); + +% Cubic Stewart platform not centered with the cube center - Jacobian estimated at the Stewart platform center +% Here, the "center" of the Stewart platform is not at the cube center. +% The Jacobian is estimated at the center of the Stewart platform. + +% The center of the cube is at $z = 110$. +% The Stewart platform is from $z = H_0 = 75$ to $z = H_0 + H_{tot} = 175$. +% The center height of the Stewart platform is then at $z = \frac{175-75}{2} = 50$. +% The center of the cube from the top platform is at $z = 110 - 175 = -65$. + + +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); + +displayArchitecture(stewart, 'labels', false); +scatter3(0, 0, FOc, 200, 'kh'); diff --git a/matlab/approximate_inverse_kinematics_validity.m b/matlab/kinematic_study_approximation_validity.m similarity index 87% rename from matlab/approximate_inverse_kinematics_validity.m rename to matlab/kinematic_study_approximation_validity.m index 5098e9d..d9ad57d 100644 --- a/matlab/approximate_inverse_kinematics_validity.m +++ b/matlab/kinematic_study_approximation_validity.m @@ -1,11 +1,16 @@ +%% Clear Workspace and Close figures +clear; close all; clc; +%% Intialize Laplace variable +s = zpk('s'); -simulinkproject('./'); +simulinkproject('../'); % Stewart architecture definition % We first define some general Stewart architecture. -stewart = initializeFramesPositions('H', 90e-3, 'MO_B', 45e-3); +stewart = initializeStewartPlatform(); +stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3); stewart = generateGeneralConfiguration(stewart); stewart = computeJointsPose(stewart); stewart = initializeStewartPose(stewart); @@ -29,7 +34,7 @@ Ls_exact = zeros(6, length(Xrs)); for i = 1:length(Xrs) Xr = Xrs(i); - L_approx(:, i) = stewart.J*[Xr; 0; 0; 0; 0; 0;]; + L_approx(:, i) = stewart.kinematics.J*[Xr; 0; 0; 0; 0; 0;]; [~, L_exact(:, i)] = inverseKinematics(stewart, 'AP', [Xr; 0; 0]); end diff --git a/matlab/mobility_from_actuator_stroke.m b/matlab/kinematic_study_mobility.m similarity index 84% rename from matlab/mobility_from_actuator_stroke.m rename to matlab/kinematic_study_mobility.m index ff54742..31d17a9 100644 --- a/matlab/mobility_from_actuator_stroke.m +++ b/matlab/kinematic_study_mobility.m @@ -1,17 +1,22 @@ +%% Clear Workspace and Close figures +clear; close all; clc; +%% Intialize Laplace variable +s = zpk('s'); -simulinkproject('./'); +simulinkproject('../'); % Stewart architecture definition % Let's first define the Stewart platform architecture that we want to study. -stewart = initializeFramesPositions('H', 90e-3, 'MO_B', 45e-3); +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, 'Ki', 1e6*ones(6,1), 'Ci', 1e2*ones(6,1)); +stewart = initializeStrutDynamics(stewart); stewart = initializeJointDynamics(stewart); stewart = computeJacobian(stewart); @@ -44,7 +49,7 @@ for i = 1:length(thetas) Ty = sin(thetas(i))*sin(phis(j)); Tz = cos(thetas(i)); - dL = stewart.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]); end diff --git a/matlab/required_stroke_from_mobility.m b/matlab/kinematic_study_required_actuator_stroke.m similarity index 88% rename from matlab/required_stroke_from_mobility.m rename to matlab/kinematic_study_required_actuator_stroke.m index 2c7a562..0cf4fbb 100644 --- a/matlab/required_stroke_from_mobility.m +++ b/matlab/kinematic_study_required_actuator_stroke.m @@ -1,17 +1,22 @@ +%% Clear Workspace and Close figures +clear; close all; clc; +%% Intialize Laplace variable +s = zpk('s'); -simulinkproject('./'); +simulinkproject('../'); % Stewart architecture definition % Let's first define the Stewart platform architecture that we want to study. -stewart = initializeFramesPositions('H', 90e-3, 'MO_B', 45e-3); +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, 'Ki', 1e6*ones(6,1), 'Ci', 1e2*ones(6,1)); +stewart = initializeStrutDynamics(stewart); stewart = initializeJointDynamics(stewart); stewart = computeJacobian(stewart); @@ -30,12 +35,12 @@ Rz_max = 0; % Rotation [rad] % We do that using either the Inverse Kinematic solution or the Jacobian matrix as an approximation. -LTx = stewart.J*[Tx_max 0 0 0 0 0]'; -LTy = stewart.J*[0 Ty_max 0 0 0 0]'; -LTz = stewart.J*[0 0 Tz_max 0 0 0]'; -LRx = stewart.J*[0 0 0 Rx_max 0 0]'; -LRy = stewart.J*[0 0 0 0 Ry_max 0]'; -LRz = stewart.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]'; diff --git a/org/active-damping.org b/org/active-damping.org index e1873c7..8e43701 100644 --- a/org/active-damping.org +++ b/org/active-damping.org @@ -51,6 +51,12 @@ The following decentralized active damping techniques are briefly studied: :END: <> +#+begin_note +The Matlab script corresponding to this section is accessible [[file:../matlab/active_damping_inertial.m][here]]. + +To run the script, open the Simulink Project, and type =run active_damping_inertial.m=. +#+end_note + ** Introduction :ignore: ** Matlab Init :noexport:ignore: #+begin_src matlab :tangle no :exports none :results silent :noweb yes :var current_dir=(file-name-directory buffer-file-name) @@ -274,6 +280,12 @@ The root locus is shown in figure [[fig:root_locus_inertial_rot_stiffness]]. :END: <> +#+begin_note +The Matlab script corresponding to this section is accessible [[file:../matlab/active_damping_iff.m][here]]. + +To run the script, open the Simulink Project, and type =run active_damping_iff.m=. +#+end_note + ** Introduction :ignore: ** Matlab Init :noexport:ignore: #+begin_src matlab :tangle no :exports none :results silent :noweb yes :var current_dir=(file-name-directory buffer-file-name) @@ -537,6 +549,12 @@ The root locus is shown in figure [[fig:root_locus_iff_rot_stiffness]] and the o :END: <> +#+begin_note +The Matlab script corresponding to this section is accessible [[file:../matlab/active_damping_dvf.m][here]]. + +To run the script, open the Simulink Project, and type =run active_damping_dvf.m=. +#+end_note + ** Introduction :ignore: ** Matlab Init :noexport:ignore: #+begin_src matlab :tangle no :exports none :results silent :noweb yes :var current_dir=(file-name-directory buffer-file-name) diff --git a/org/cubic-configuration.org b/org/cubic-configuration.org index f2270aa..877cf41 100644 --- a/org/cubic-configuration.org +++ b/org/cubic-configuration.org @@ -57,7 +57,18 @@ In this document, the cubic architecture is analyzed: - In section [[sec:functions]], function related to the cubic configuration are defined. To generate and study the Stewart platform with a Cubic configuration, the Matlab function =generateCubicConfiguration= is used (described [[sec:generateCubicConfiguration][here]]). * Stiffness Matrix for the Cubic configuration +:PROPERTIES: +:header-args:matlab+: :tangle ../matlab/cubic_conf_stiffnessl.m +:header-args:matlab+: :comments org :mkdirp yes +:END: <> + +#+begin_note +The Matlab script corresponding to this section is accessible [[file:../matlab/cubic_conf_stiffnessl.m][here]]. + +To run the script, open the Simulink Project, and type =run cubic_conf_stiffness.m=. +#+end_note + ** Introduction :ignore: First, we have to understand what is the physical meaning of the Stiffness matrix $\bm{K}$. @@ -301,7 +312,18 @@ Here are the conclusion about the Stiffness matrix for the Cubic configuration: #+end_important * Configuration with the Cube's center above the mobile platform +:PROPERTIES: +:header-args:matlab+: :tangle ../matlab/cubic_conf_above_platforml.m +:header-args:matlab+: :comments org :mkdirp yes +:END: <> + +#+begin_note +The Matlab script corresponding to this section is accessible [[file:../matlab/cubic_conf_above_platforml.m][here]]. + +To run the script, open the Simulink Project, and type =run cubic_conf_above_platform.m=. +#+end_note + ** Introduction :ignore: We saw in section [[sec:cubic_conf_stiffness]] that in order to have a diagonal stiffness matrix, we need the cube's center to be located at frames $\{A\}$ and $\{B\}$. Or, we usually want to have $\{A\}$ and $\{B\}$ located above the top platform where forces are applied and where displacements are expressed. @@ -469,7 +491,18 @@ However, the rotational stiffnesses are increasing with the cube's size but the #+end_important * Cubic size analysis +:PROPERTIES: +:header-args:matlab+: :tangle ../matlab/cubic_conf_size_analysisl.m +:header-args:matlab+: :comments org :mkdirp yes +:END: <> + +#+begin_note +The Matlab script corresponding to this section is accessible [[file:../matlab/cubic_conf_size_analysisl.m][here]]. + +To run the script, open the Simulink Project, and type =run cubic_conf_size_analysis.m=. +#+end_note + ** Introduction :ignore: We here study the effect of the size of the cube used for the Stewart Cubic configuration. @@ -553,7 +586,18 @@ We observe that $k_{\theta_x} = k_{\theta_y}$ and $k_{\theta_z}$ increase linear #+end_important * Dynamic Coupling in the Cartesian Frame +:PROPERTIES: +:header-args:matlab+: :tangle ../matlab/cubic_conf_coupling_cartesianl.m +:header-args:matlab+: :comments org :mkdirp yes +:END: <> + +#+begin_note +The Matlab script corresponding to this section is accessible [[file:../matlab/cubic_conf_coupling_cartesianl.m][here]]. + +To run the script, open the Simulink Project, and type =run cubic_conf_coupling_cartesian.m=. +#+end_note + ** Introduction :ignore: In this section, we study the dynamics of the platform in the cartesian frame. @@ -980,7 +1024,18 @@ Some conclusions can be drawn from the above analysis: #+end_important * Dynamic Coupling between actuators and sensors of each strut +:PROPERTIES: +:header-args:matlab+: :tangle ../matlab/cubic_conf_coupling_strutsl.m +:header-args:matlab+: :comments org :mkdirp yes +:END: <> + +#+begin_note +The Matlab script corresponding to this section is accessible [[file:../matlab/cubic_conf_coupling_strutsl.m][here]]. + +To run the script, open the Simulink Project, and type =run cubic_conf_coupling_struts.m=. +#+end_note + ** Introduction :ignore: From cite:preumont07_six_axis_singl_stage_activ, the cubic configuration "/minimizes the cross-coupling amongst actuators and sensors of different legs (being orthogonal to each other)/". diff --git a/org/kinematic-study.org b/org/kinematic-study.org index 1aa1864..4a988e4 100644 --- a/org/kinematic-study.org +++ b/org/kinematic-study.org @@ -49,7 +49,8 @@ The current document is divided in the following sections: - Section [[sec:jacobian_analysis]]: The Jacobian matrix is derived from the geometry of the Stewart platform. Then it is shown that the Jacobian can link velocities and forces present in the system, and thus this matrix can be very useful for both analysis and control of the Stewart platform. - Section [[sec:stiffness_analysis]]: The stiffness and compliance matrices are derived from the Jacobian matrix and the stiffness of each strut. - Section [[sec:forward_inverse_kinematics]]: The Forward and Inverse kinematic problems are presented. -- Section [[sec:required_actuator_stroke]]: The Inverse kinematic solution is used to estimate required actuator stroke from the wanted mobility of the Stewart platform. +- Section [[sec:kinematic_study_approximation_validity]]: The approximate solution of the Inverse kinematic problem is compared with the exact solution in order to determine the validity of the approximation. +- Section [[sec:kinematic_study_required_actuator_stroke]]: The Inverse kinematic solution is used to estimate required actuator stroke from the wanted mobility of the Stewart platform. * Jacobian Analysis <> @@ -213,14 +214,20 @@ As the inverse kinematic can be easily solved exactly this is not much useful, h The function =forwardKinematicsApprox= (described [[sec:forwardKinematicsApprox][here]]) can be used to solve the forward kinematic problem using the Jacobian matrix. -** Estimation of the range validity of the approximate inverse kinematics +* Estimation of the range validity of the approximate inverse kinematics :PROPERTIES: -:header-args:matlab+: :tangle ../matlab/approximate_inverse_kinematics_validity.m +:header-args:matlab+: :tangle ../matlab/kinematic_study_approximation_validity.m :header-args:matlab+: :comments org :mkdirp yes :END: -<> +<> -*** Introduction :ignore: +#+begin_note +The Matlab script corresponding to this section is accessible [[file:../matlab/kinematic_study_approximation_validity.m][here]]. + +To run the script, open the Simulink Project, and type =run kinematic_study_approximation_validity.m=. +#+end_note + +** Introduction :ignore: As we know how to exactly solve the Inverse kinematic problem, we can compare the exact solution with the approximate solution using the Jacobian matrix. For small displacements, the approximate solution is expected to work well. We would like here to determine up to what displacement this approximation can be considered as correct. @@ -228,7 +235,7 @@ We would like here to determine up to what displacement this approximation can b Then, we can determine the range for which the approximate inverse kinematic is valid. This will also gives us the range for which the approximate forward kinematic is valid. -*** Matlab Init :noexport:ignore: +** Matlab Init :noexport:ignore: #+begin_src matlab :tangle no :exports none :results silent :noweb yes :var current_dir=(file-name-directory buffer-file-name) <> #+end_src @@ -241,7 +248,7 @@ This will also gives us the range for which the approximate forward kinematic is simulinkproject('../'); #+end_src -*** Stewart architecture definition +** Stewart architecture definition We first define some general Stewart architecture. #+begin_src matlab stewart = initializeStewartPlatform(); @@ -256,7 +263,7 @@ We first define some general Stewart architecture. stewart = computeJacobian(stewart); #+end_src -*** Comparison for "pure" translations +** Comparison for "pure" translations Let's first compare the perfect and approximate solution of the inverse for pure $x$ translations. We compute the approximate and exact required strut stroke to have the wanted mobile platform $x$ displacement. @@ -320,17 +327,24 @@ The relative strut length displacement is shown in Figure [[fig:inverse_kinemati #+CAPTION: Relative length error by using the Approximate solution of the Inverse kinematic problem ([[./figs/inverse_kinematics_approx_validity_x_translation_relative.png][png]], [[./figs/inverse_kinematics_approx_validity_x_translation_relative.pdf][pdf]]) [[file:figs/inverse_kinematics_approx_validity_x_translation_relative.png]] -*** Conclusion +** Conclusion #+begin_important 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. #+end_important * Estimated required actuator stroke from specified platform mobility :PROPERTIES: -:header-args:matlab+: :tangle ../matlab/required_stroke_from_mobility.m +:header-args:matlab+: :tangle ../matlab/kinematic_study_required_actuator_stroke.m :header-args:matlab+: :comments org :mkdirp yes :END: -<> +<> + +#+begin_note +The Matlab script corresponding to this section is accessible [[file:../matlab/kinematic_study_required_actuator_stroke.m][here]]. + +To run the script, open the Simulink Project, and type =run kinematic_study_required_actuator_stroke.m=. +#+end_note + ** Introduction :ignore: Let's say one want to design a Stewart platform with some specified mobility (position and orientation). One may want to determine the required actuator stroke required to obtain the specified mobility. @@ -483,10 +497,17 @@ This is probably a much realistic estimation of the required actuator stroke. * Estimated platform mobility from specified actuator stroke :PROPERTIES: -:header-args:matlab+: :tangle ../matlab/mobility_from_actuator_stroke.m +:header-args:matlab+: :tangle ../matlab/kinematic_study_mobility.m :header-args:matlab+: :comments org :mkdirp yes :END: -<> +<> + +#+begin_note +The Matlab script corresponding to this section is accessible [[file:../matlab/kinematic_study_mobility.m][here]]. + +To run the script, open the Simulink Project, and type =run kinematic_study_mobility.m=. +#+end_note + ** Introduction :ignore: Here, from some value of the actuator stroke, we would like to estimate the mobility of the Stewart platform.