UP | HOME

Table of Contents

Stewart Platform - Tracking Control

Table of ContentsClose

Let’s suppose the control objective is to position X of the mobile platform of the Stewart platform such that it is following some reference position rX.

In order to compute the pose error ϵX from the actual pose X and the reference position rX, some computation is required and explained in section 5.

Depending of the measured quantity, different control architectures can be used:

The control configuration are compare in section 4.

1 Decentralized Control Architecture using Strut Length

1.1 Control Schematic

The control architecture is shown in Figure 1.

The required leg length rL is computed from the reference path rX using the inverse kinematics.

Then, a diagonal (decentralized) controller KL is used such that each leg lengths stays close to its required length.

decentralized_reference_tracking_L.png

Figure 1: Decentralized control for reference tracking

1.2 Initialize the Stewart platform

Copy
% 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);

1.3 Identification of the plant

Let’s identify the transfer function from τ to L.

Copy
%% 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); G.InputName = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'}; G.OutputName = {'L1', 'L2', 'L3', 'L4', 'L5', 'L6'};

1.4 Plant Analysis

The diagonal and off-diagonal terms of the plant are shown in Figure 2.

All the diagonal terms are equal. We see that the plant is decoupled at low frequency which indicate that decentralized control may be a good idea.

plant_decentralized_L.png

Figure 2: Obtain Diagonal and off diagonal dynamics (png, pdf)

1.5 Controller Design

The controller consists of:

  • A pure integrator
  • A low pass filter with a cut-off frequency 3 times the crossover to increase the gain margin

The obtained loop gains corresponding to the diagonal elements are shown in Figure 3.

Copy
wc = 2*pi*30; Kl = diag(1./diag(abs(freqresp(G, wc)))) * wc/s * 1/(1 + s/3/wc);

loop_gain_decentralized_L.png

Figure 3: Loop Gain of the diagonal elements (png, pdf)

1.6 Simulation

Let’s define some reference path to follow.

Copy
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);

The reference path is shown in Figure 4.

Copy
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]');

tracking_control_reference_path.png

Figure 4: Reference path used for Tracking control (png, pdf)

Copy
controller = initializeController('type', 'ref-track-L');
Copy
set_param('stewart_platform_model', 'StopTime', '10') sim('stewart_platform_model'); simout_D = simout;
Copy
save('./mat/control_tracking.mat', 'simout_D', '-append');

1.7 Results

The reference path and the position of the mobile platform are shown in Figure 5.

Copy
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]);

decentralized_control_3d_pos.png

Figure 5: Reference path and Obtained Position (png, pdf)

decentralized_control_Ex.png

Figure 6: Position error ϵX (png, pdf)

decentralized_control_El.png

Figure 7: Position error ϵL (png, pdf)

1.8 Conclusion

Such control architecture is easy to implement and give good results. The inverse kinematics is easy to compute.

However, as X is not directly measured, it is possible that important positioning errors are due to finite stiffness of the joints and other imperfections.

2 Centralized Control Architecture using Pose Measurement

2.1 Control Schematic

The centralized controller takes the position error ϵX as an inputs and generate actuator forces τ (see Figure 8). The signals are:

  • reference path rX=[ϵxϵyϵzϵRxϵRyϵRz]
  • tracking error ϵX=[ϵxϵyϵzϵRxϵRyϵRz]
  • actuator forces τ=[τ1τ2τ3τ4τ5τ6]
  • payload pose X=[xyzRxRyRz]

centralized_reference_tracking.png

Figure 8: Centralized Controller

Instead of designing a full MIMO controller K, we first try to make the plant more diagonal by pre- or post-multiplying some constant matrix, then we design a diagonal controller.

We can think of two ways to make the plant more diagonal that are described in sections 2.4 and 2.5.

Important

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.

2.2 Initialize the Stewart platform

Copy
% 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

Let’s identify the transfer function from τ to X.

Copy
%% 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] %% 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 Diagonal Control - Leg’s Frame

2.4.1 Control Architecture

The pose error ϵX is first converted in the frame of the leg by using the Jacobian matrix. Then a diagonal controller KL is designed. The final implemented controller is K=KLJ as shown in Figure 9

Note here that the transformation from the pose error ϵX to the leg’s length errors by using the Jacobian matrix is only valid for small errors.

centralized_reference_tracking_L.png

Figure 9: Controller in the frame of the legs

2.4.2 Plant Analysis

We now multiply the plant by the Jacobian matrix as shown in Figure 9 to obtain a more diagonal plant.

Copy
Gl = stewart.kinematics.J*G; Gl.OutputName = {'D1', 'D2', 'D3', 'D4', 'D5', 'D6'};

The bode plot of the plant is shown in Figure 10. We can see that the diagonal elements are identical. This will simplify the design of the controller as all the elements of the diagonal controller can be made identical.

plant_centralized_L.png

Figure 10: Diagonal and off-diagonal elements of the plant JG (png, pdf)

We can see that this totally decouples the system at low frequency.

This was expected since: G(ω=0)=δXδτ(ω=0)=J1δLδτ(ω=0)=J1diag(K11  K61)

Thus JG(ω=0)=JδXδτ(ω=0) is a diagonal matrix containing the inverse of the joint’s stiffness.

2.4.3 Controller Design

The controller consists of:

  • A pure integrator
  • A low pass filter with a cut-off frequency 3 times the crossover to increase the gain margin

The obtained loop gains corresponding to the diagonal elements are shown in Figure 11.

Copy
wc = 2*pi*30; Kl = diag(1./diag(abs(freqresp(Gl, wc)))) * wc/s * 1/(1 + s/3/wc);

loop_gain_centralized_L.png

Figure 11: Loop Gain of the diagonal elements (png, pdf)

The controller K=KLJ is computed.

Copy
K = Kl*stewart.kinematics.J;

2.4.4 Simulation

We specify the reference path to follow.

Copy
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);
Copy
controller = initializeController('type', 'ref-track-X');

We run the simulation and we save the results.

Copy
set_param('stewart_platform_model', 'StopTime', '10') sim('stewart_platform_model') simout_L = simout; save('./mat/control_tracking.mat', 'simout_L', '-append');

2.5 Diagonal Control - Cartesian Frame

2.5.1 Control Architecture

A diagonal controller KX take the pose error ϵX and generate cartesian forces F that are then converted to actuators forces using the Jacobian as shown in Figure e 12.

The final implemented controller is K=JTKX.

centralized_reference_tracking_X.png

Figure 12: Controller in the cartesian frame

2.5.2 Plant Analysis

We now multiply the plant by the Jacobian matrix as shown in Figure 12 to obtain a more diagonal plant.

Copy
Gx = G*inv(stewart.kinematics.J'); Gx.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};

plant_centralized_X.png

Figure 13: Diagonal and off-diagonal elements of the plant GJT (png, pdf)

The diagonal terms are not the same. The resonances of the system are “decoupled”. For instance, the vertical resonance of the system is only present on the diagonal term corresponding to Dz/Fz.

Here the system is almost decoupled at all frequencies except for the transfer functions RyFx and RxFy.

This is due to the fact that the compliance matrix of the Stewart platform is not diagonal.

4.75e-08 -1.9751e-24 7.3536e-25 5.915e-23 3.2093e-07 5.8696e-24
-7.1302e-25 4.75e-08 2.8866e-25 -3.2093e-07 -5.38e-24 -3.2725e-23
7.9012e-26 -6.3991e-25 2.099e-08 1.9073e-23 5.3384e-25 -6.4867e-40
1.3724e-23 -3.2093e-07 1.2799e-23 5.1863e-06 4.9412e-22 -3.8269e-24
3.2093e-07 7.6013e-24 1.2239e-23 6.8886e-22 5.1863e-06 -2.6025e-22
7.337e-24 -3.2395e-23 -1.571e-39 9.927e-23 -3.2531e-22 1.7073e-06

One way to have this compliance matrix diagonal (and thus having a decoupled plant at DC) is to use a cubic architecture with the center of the cube’s coincident with frame {A}.

This control architecture can also give a dynamically decoupled plant if the Center of mass of the payload is also coincident with frame {A}.

2.5.3 Controller Design

The controller consists of:

  • A pure integrator
  • A low pass filter with a cut-off frequency 3 times the crossover to increase the gain margin

The obtained loop gains corresponding to the diagonal elements are shown in Figure 14.

Copy
wc = 2*pi*30; Kx = diag(1./diag(abs(freqresp(Gx, wc)))) * wc/s * 1/(1 + s/3/wc);

loop_gain_centralized_X.png

Figure 14: Loop Gain of the diagonal elements (png, pdf)

The controller K=JTKX is computed.

Copy
K = inv(stewart.kinematics.J')*Kx;

2.5.4 Simulation

We specify the reference path to follow.

Copy
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);
Copy
controller = initializeController('type', 'ref-track-X');

We run the simulation and we save the results.

Copy
set_param('stewart_platform_model', 'StopTime', '10') sim('stewart_platform_model') simout_X = simout; save('./mat/control_tracking.mat', 'simout_X', '-append');

2.6 Diagonal Control - Steady State Decoupling

2.6.1 Control Architecture

The plant G is pre-multiply by G1(ω=0) such that the “shaped plant” G0=GG1(ω=0) is diagonal at low frequency.

Then a diagonal controller K0 is designed.

The control architecture is shown in Figure 15.

centralized_reference_tracking_S.png

Figure 15: Static Decoupling of the Plant

2.6.2 Plant Analysis

The plant is pre-multiplied by G1(ω=0). The diagonal and off-diagonal elements of the shaped plant are shown in Figure 16.

Copy
G0 = G*inv(freqresp(G, 0));

plant_centralized_SD.png

Figure 16: Diagonal and off-diagonal elements of the plant GG1(ω=0) (png, pdf)

2.6.3 Controller Design

We have that: G1(ω=0)=(δXδτ(ω=0))1=(J1δLδτ(ω=0))1=diag(K11  K61)J

And because:

  • all the leg stiffness are equal
  • the controller equal to a K0(s)=k(s)I6

We have that K0(s) commutes with G1(ω=0) and thus the overall controller K is the same as the one obtain in section 2.4.

2.7 Comparison

2.7.1 Obtained MIMO Controllers

centralized_control_comp_K.png

Figure 17: Comparison of the MIMO controller K for both centralized architectures (png, pdf)

2.7.2 Simulation Results

The position error ϵX for both centralized architecture are shown in Figure 18.

Based on Figure 18, we can see that:

  • There is some tracking error ϵx
  • The errors ϵy, ϵRx and ϵRz are quite negligible
  • There is some error in the vertical position ϵz. The frequency of the error ϵz is twice the frequency of the reference path rx.
  • There is some error ϵRy. This error is much lower when using the diagonal control in the frame of the leg instead of the cartesian frame.

centralized_control_comp_Ex.png

Figure 18: Comparison of the position error ϵX for both centralized controllers (png, pdf)

2.8 Conclusion

Both control architecture gives similar results even tough the control in the Leg’s frame gives slightly better results.

The main differences between the control architectures used in sections 2.4 and 2.5 are summarized in Table 1.

Table 1: Comparison of the two centralized control architectures
  Leg’s Frame Cartesian Frame Static Decoupling
Plant Meaning δLi/τi δXi/Fi No physical meaning
Obtained Decoupling Decoupled at DC Dynamical decoupling except few terms Decoupled at DC
Diagonal Elements Identical with all the Resonances Different, resonances are cancel out No Alternating poles and zeros
Mechanical Architecture Architecture Independent Better with Cubic Architecture  
Robustness to Uncertainty Good (only depends on J) Good (only depends on J) Bad (depends on the mass)

These decoupling methods only uses the Jacobian matrix which only depends on the Stewart platform geometry. Thus, this method should be quite robust against parameter variation (e.g. the payload mass).

3 Hybrid Control Architecture - HAC-LAC with relative DVF

3.1 Control Schematic

Let’s consider the control schematic shown in Figure 19.

The first loop containing KL is a Decentralized Direct (Relative) Velocity Feedback.

A reference rL is computed using the inverse kinematics and corresponds to the wanted motion of each leg. The actual length of each leg L is subtracted and then passed trough the controller KL.

The controller is a diagonal controller with pure derivative action on the diagonal.

The effect of this loop is:

  • it adds damping to the system (the force applied in each actuator is proportional to the relative velocity of the strut)
  • it however does not go “against” the reference path rX thanks to the use of the inverse kinematics

Then, the second loop containing KX is designed based on the already damped plant (represented by the gray area). This second loop is responsible for the reference tracking.

hybrid_reference_tracking.png

Figure 19: Hybrid Control Architecture

3.2 Initialize the Stewart platform

Copy
% 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 - KL

3.3.1 Identification

Let’s identify the transfer function from τ to L.

Copy
%% 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 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

The obtained plant is shown in Figure 20.

hybrid_control_Kl_plant.png

Figure 20: Diagonal and off-diagonal elements of the plant for the design of KL (png, pdf)

3.3.3 Controller Design

We apply a decentralized (diagonal) direct velocity feedback. Thus, we apply a pure derivative action. In order to make the controller realizable, we add a low pass filter at high frequency. The gain of the controller is chosen such that the resonances are critically damped.

The obtain loop gain is shown in Figure 21.

Copy
Kl = 1e4 * s / (1 + s/2/pi/1e4) * eye(6);

hybrid_control_Kl_loop_gain.png

Figure 21: Obtain Loop Gain for the DVF control loop (png, pdf)

3.4 Second Control Loop - KX

3.4.1 Identification

Copy
Kx = tf(zeros(6)); controller = initializeController('type', 'ref-track-hac-dvf');
Copy
%% 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] %% 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

We use the Jacobian matrix to apply forces in the cartesian frame.

Copy
Gx = G*inv(stewart.kinematics.J'); Gx.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};

The obtained plant is shown in Figure 22.

hybrid_control_Kx_plant.png

Figure 22: Diagonal and Off-diagonal elements of the plant for the design of KL (png, pdf)

3.4.3 Controller Design

The controller consists of:

  • A pure integrator
  • A Second integrator up to half the wanted bandwidth
  • A Lead around the cross-over frequency
  • A low pass filter with a cut-off equal to three times the wanted bandwidth
Copy
wc = 2*pi*200; % Bandwidth Bandwidth [rad/s] 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)); % Normalization of the gain of have a loop gain of 1 at frequency wc Kx = Kx.*diag(1./diag(abs(freqresp(Gx*Kx, wc))));

hybrid_control_Kx_loop_gain.png

Figure 23: Obtained Loop Gain for the controller KX (png, pdf)

Then we include the Jacobian in the controller matrix.

Copy
Kx = inv(stewart.kinematics.J')*Kx;

3.5 Simulations

We specify the reference path to follow.

Copy
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);

We run the simulation and we save the results.

Copy
set_param('stewart_platform_model', 'StopTime', '10') sim('stewart_platform_model') simout_H = simout; save('./mat/control_tracking.mat', 'simout_H', '-append');

The obtained position error is shown in Figure 24.

hybrid_control_Ex.png

Figure 24: Obtained position error ϵX (png, pdf)

3.6 Conclusion

4 Comparison of all the methods

Let’s load the simulation results and compare them in Figure 25.

Copy
load('./mat/control_tracking.mat', 'simout_D', 'simout_L', 'simout_X', 'simout_H');

reference_tracking_performance_comparison.png

Figure 25: Comparison of the position errors for all the Control architecture used (png, pdf)

5 Compute the pose error of the Stewart Platform

Let’s note:

  • {W} the fixed measurement frame (corresponding to the metrology frame / the frame where the wanted displacement are expressed). The center of the frame if OW
  • {M} is the frame fixed to the measured elements. OM is the point where the pose of the element is measured
  • {R} is a virtual frame corresponding to the wanted pose of the element. OR is the origin of this frame where the we want to position the point OM of the element.
  • {V} is a frame which its axes are aligned with {W} and its origin OV is coincident with the OM

Reference Position with respect to fixed frame {W}: WTR

Copy
Dxr = 0; Dyr = 0; Dzr = 0.1; Rxr = pi; Ryr = 0; Rzr = 0;

Measured Position with respect to fixed frame {W}: WTM

Copy
Dxm = 0; Dym = 0; Dzm = 0; Rxm = pi; Rym = 0; Rzm = 0;

We measure the position and orientation (pose) of the element represented by the frame {M} with respect to frame {W}. Thus we can compute the Homogeneous transformation matrix WTM.

Copy
%% 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];

We can also compute the Homogeneous transformation matrix WTR corresponding to the transformation required to go from fixed frame {W} to the wanted frame {R}.

Copy
%% 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];

We can also compute WTV.

Copy
WTv = eye(4); WTv(1:3, 4) = WTm(1:3, 4);

Now we want to express MTR which corresponds to the transformation required to go to wanted position expressed in the frame of the measured element. This homogeneous transformation can be computed from the previously computed matrices: MTR=(WTM1)WTR

Copy
%% 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;

Now we want to express VTR: VTR=(WTV1)WTR

Copy
%% 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;
Copy
%% 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));

Author: Dehaeze Thomas

Created: 2021-01-08 ven. 15:53