diff --git a/docs/control-tracking.html b/docs/control-tracking.html index 4ea878b..6f71fe6 100644 --- a/docs/control-tracking.html +++ b/docs/control-tracking.html @@ -4,7 +4,7 @@ "http://www.w3.org/TR/xhtml1/DTD/xhtml1-strict.dtd">
- ++In order to compute the pose error \(\bm{\epsilon}_\mathcal{X}\) from the actual pose \(\bm{\mathcal{X}}\) and the reference position \(\bm{r}_\mathcal{X}\), some computation is required and explained in section 5. +
+Depending of the measured quantity, different control architectures can be used:
@@ -335,6 +340,10 @@ Depending of the measured quantity, different control architectures can be used:+The control configuration are compare in section 4. +
+The control architecture is shown in Figure 1. @@ -366,11 +375,12 @@ Then, a diagonal (decentralized) controller \(\bm{K}_\mathcal{L}\) is used such
stewart = initializeStewartPlatform(); +% Stewart Platform +stewart = initializeStewartPlatform(); stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3); stewart = generateGeneralConfiguration(stewart); stewart = computeJointsPose(stewart); @@ -381,26 +391,24 @@ stewart = initializeCylindricalStruts(stewart); stewart = computeJacobian(stewart); stewart = initializeStewartPose(stewart); stewart = initializeInertialSensor(stewart, 'type', 'accelerometer', 'freq', 5e3); --
ground = initializeGround('type', 'rigid'); +% Ground and Payload +ground = initializeGround('type', 'rigid'); payload = initializePayload('type', 'none'); -controller = initializeController('type', 'open-loop'); --
disturbances = initializeDisturbances(); +% Controller +controller = initializeController('type', 'open-loop'); + +% Disturbances and References +disturbances = initializeDisturbances(); references = initializeReferences(stewart);
Let’s identify the transfer function from \(\bm{\tau}\) to \(\bm{\mathcal{L}}\). @@ -423,8 +431,8 @@ G.OutputName = {'L1', '
The diagonal terms of the plant is shown in Figure 2. @@ -458,8 +466,8 @@ We see that the plant is decoupled at low frequency which indicate that decentra
The controller consists of: @@ -488,54 +496,108 @@ Kl = diag(1./diag(abs(freqresp(G, wc))))
+Let’s define some reference path to follow. +
t = linspace(0, 10, 1000); +t = [0:1e-4:10]; r = zeros(6, length(t)); -r(1, :) = 5e-3*sin(2*pi*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 5. +
+ +figure; +plot3(squeeze(references.r.Data(1,1,:)), squeeze(references.r.Data(2,1,:)), squeeze(references.r.Data(3,1,:))); +xlabel('X [m]'); +ylabel('Y [m]'); +zlabel('Z [m]'); ++
controller = initializeController('type', 'ref-track-L');
sim('stewart_platform_model') +set_param('stewart_platform_model', 'StopTime', '10') +sim('stewart_platform_model'); simout_D = simout;
save('./mat/control_tracking.mat', 'simout_D', '-append'); ++
+The reference path and the position of the mobile platform are shown in Figure 6. +
+ +figure; +hold on; +plot3(simout_D.x.Xr.Data(:, 1), simout_D.x.Xr.Data(:, 2), simout_D.x.Xr.Data(:, 3), 'k-'); +plot3(squeeze(references.r.Data(1,1,:)), squeeze(references.r.Data(2,1,:)), squeeze(references.r.Data(3,1,:)), '--'); +hold off; +xlabel('X [m]'); ylabel('Y [m]'); zlabel('Z [m]'); +view([1,1,1]) +zlim([0, inf]); ++
Such control architecture is easy to implement and give good results. @@ -556,11 +618,11 @@ However, as \(\mathcal{X}\) is not directly measured, it is possible that import
-The centralized controller takes the position error \(\bm{\epsilon}_\mathcal{X}\) as an inputs and generate actuator forces \(\bm{\tau}\) (see Figure 7). +The centralized controller takes the position error \(\bm{\epsilon}_\mathcal{X}\) as an inputs and generate actuator forces \(\bm{\tau}\) (see Figure 9). The signals are:
-
Figure 7: Centralized Controller
+Figure 9: Centralized Controller
@@ -587,19 +649,20 @@ We can think of two ways to make the plant more diagonal that are described in s
stewart = initializeStewartPlatform(); +% Stewart Platform +stewart = initializeStewartPlatform(); stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3); stewart = generateGeneralConfiguration(stewart); stewart = computeJointsPose(stewart); @@ -610,26 +673,24 @@ stewart = initializeCylindricalStruts(stewart); stewart = computeJacobian(stewart); stewart = initializeStewartPose(stewart); stewart = initializeInertialSensor(stewart, 'type', 'accelerometer', 'freq', 5e3); --
ground = initializeGround('type', 'rigid'); +% Ground and Payload +ground = initializeGround('type', 'rigid'); payload = initializePayload('type', 'none'); -controller = initializeController('type', 'open-loop'); --
disturbances = initializeDisturbances(); +% Controller +controller = initializeController('type', 'open-loop'); + +% Disturbances and References +disturbances = initializeDisturbances(); references = initializeReferences(stewart);
Let’s identify the transfer function from \(\bm{\tau}\) to \(\bm{\mathcal{X}}\). @@ -659,13 +720,13 @@ G.OutputName = {'Dx', '
The pose error \(\bm{\epsilon}_\mathcal{X}\) is first converted in the frame of the leg by using the Jacobian matrix. Then a diagonal controller \(\bm{K}_\mathcal{L}\) is designed. -The final implemented controller is \(\bm{K} = \bm{K}_\mathcal{L} \cdot \bm{J}\) as shown in Figure 8 +The final implemented controller is \(\bm{K} = \bm{K}_\mathcal{L} \cdot \bm{J}\) as shown in Figure 10
@@ -676,16 +737,16 @@ Note here that the transformation from the pose error \(\bm{\epsilon}_\mathcal{X
-
Figure 8: Controller in the frame of the legs
+Figure 10: Controller in the frame of the legs
-We now multiply the plant by the Jacobian matrix as shown in Figure 8 to obtain a more diagonal plant. +We now multiply the plant by the Jacobian matrix as shown in Figure 10 to obtain a more diagonal plant.
-
Figure 9: Diagonal Elements of the plant \(\bm{J} \bm{G}\) (png, pdf)
+Figure 11: Diagonal Elements of the plant \(\bm{J} \bm{G}\) (png, pdf)
@@ -707,14 +768,14 @@ This will simplify the design of the controller as all the elements of the diago
-The off-diagonal terms of the controller are shown in Figure 10. +The off-diagonal terms of the controller are shown in Figure 12.
-
Figure 10: Off Diagonal Elements of the plant \(\bm{J} \bm{G}\) (png, pdf)
+Figure 12: Off Diagonal Elements of the plant \(\bm{J} \bm{G}\) (png, pdf)
@@ -732,8 +793,8 @@ Thus \(J \cdot G(\omega = 0) = J \cdot \frac{\delta\bm{\mathcal{X}}}{\delta\bm{\
The controller consists of: @@ -744,7 +805,7 @@ The controller consists of:
-The obtained loop gains corresponding to the diagonal elements are shown in Figure 11. +The obtained loop gains corresponding to the diagonal elements are shown in Figure 13.
- +
@@ -770,18 +831,20 @@ The controller \(\bm{K} = \bm{K}_\mathcal{L} \bm{J}\) is computed.
We specify the reference path to follow.
t = linspace(0, 10, 1000); +t = [0:1e-4:10]; r = zeros(6, length(t)); -r(1, :) = 5e-3*sin(2*pi*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);@@ -796,8 +859,10 @@ references = initializeReferences(stewart, 't', We run the simulation and we save the results.-sim('stewart_platform_model') +set_param('stewart_platform_model', 'StopTime', '10') +sim('stewart_platform_model') simout_L = simout; +save('./mat/control_tracking.mat', 'simout_L', '-append');
-A diagonal controller \(\bm{K}_\mathcal{X}\) take the pose error \(\bm{\epsilon}_\mathcal{X}\) and generate cartesian forces \(\bm{\mathcal{F}}\) that are then converted to actuators forces using the Jacobian as shown in Figure e 12. +A diagonal controller \(\bm{K}_\mathcal{X}\) take the pose error \(\bm{\epsilon}_\mathcal{X}\) and generate cartesian forces \(\bm{\mathcal{F}}\) that are then converted to actuators forces using the Jacobian as shown in Figure e 14.
@@ -826,16 +891,16 @@ The final implemented controller is \(\bm{K} = \bm{J}^{-T} \cdot \bm{K}_\mathcal
-
Figure 12: Controller in the cartesian frame
+Figure 14: Controller in the cartesian frame
-We now multiply the plant by the Jacobian matrix as shown in Figure 12 to obtain a more diagonal plant. +We now multiply the plant by the Jacobian matrix as shown in Figure 14 to obtain a more diagonal plant.
-
Figure 13: Diagonal Elements of the plant \(\bm{G} \bm{J}^{-T}\) (png, pdf)
+Figure 15: Diagonal Elements of the plant \(\bm{G} \bm{J}^{-T}\) (png, pdf)
@@ -861,7 +926,7 @@ For instance, the vertical resonance of the system is only present on the diagon
-
Figure 14: Off Diagonal Elements of the plant \(\bm{G} \bm{J}^{-T}\) (png, pdf)
+Figure 16: Off Diagonal Elements of the plant \(\bm{G} \bm{J}^{-T}\) (png, pdf)
@@ -954,8 +1019,8 @@ This control architecture can also give a dynamically decoupled plant if the Cen
The controller consists of: @@ -966,7 +1031,7 @@ The controller consists of:
-The obtained loop gains corresponding to the diagonal elements are shown in Figure 15. +The obtained loop gains corresponding to the diagonal elements are shown in Figure 17.
- +
@@ -992,18 +1057,20 @@ The controller \(\bm{K} = \bm{J}^{-T} \bm{K}_\mathcal{X}\) is computed.
We specify the reference path to follow.
t = linspace(0, 10, 1000); +t = [0:1e-4:10]; r = zeros(6, length(t)); -r(1, :) = 5e-3*sin(2*pi*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);@@ -1018,8 +1085,10 @@ references = initializeReferences(stewart, 't', We run the simulation and we save the results.-sim('stewart_platform_model') +set_param('stewart_platform_model', 'StopTime', '10') +sim('stewart_platform_model') simout_X = simout; +save('./mat/control_tracking.mat', 'simout_X', '-append');
The plant \(\bm{G}\) is pre-multiply by \(\bm{G}^{-1}(\omega = 0)\) such that the “shaped plant” \(\bm{G}_0 = \bm{G} \bm{G}^{-1}(\omega = 0)\) is diagonal at low frequency. @@ -1045,24 +1114,24 @@ Then a diagonal controller \(\bm{K}_0\) is designed.
-The control architecture is shown in Figure 16. +The control architecture is shown in Figure 18.
-
Figure 16: Static Decoupling of the Plant
+Figure 18: Static Decoupling of the Plant
The plant is pre-multiplied by \(\bm{G}^{-1}(\omega = 0)\). -The diagonal elements of the shaped plant are shown in Figure 17. +The diagonal elements of the shaped plant are shown in Figure 19.
-
Figure 17: Diagonal Elements of the plant \(\bm{G} \bm{G}^{-1}(\omega = 0)\) (png, pdf)
+Figure 19: Diagonal Elements of the plant \(\bm{G} \bm{G}^{-1}(\omega = 0)\) (png, pdf)
We have that: @@ -1119,7 +1188,7 @@ We have that \(\bm{K}_0(s)\) commutes with \(\bm{G}^{-1}(\omega = 0)\) and thus
-The position error \(\bm{\epsilon}_\mathcal{X}\) for both centralized architecture are shown in Figure 20. -The corresponding leg’s length errors \(\bm{\epsilon}_\mathcal{L}\) are shown in Figure 21. +The position error \(\bm{\epsilon}_\mathcal{X}\) for both centralized architecture are shown in Figure 22.
-Based on Figure 20, we can see that: +Based on Figure 22, we can see that:
Both control architecture gives similar results even tough the control in the Leg’s frame gives slightly better results. @@ -1245,11 +1306,11 @@ Thus, this method should be quite robust against parameter variation (e.g. the p
stewart = initializeStewartPlatform(); +% Stewart Platform +stewart = initializeStewartPlatform(); stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3); stewart = generateGeneralConfiguration(stewart); stewart = computeJointsPose(stewart); @@ -1302,18 +1364,16 @@ stewart = initializeCylindricalStruts(stewart); stewart = computeJacobian(stewart); stewart = initializeStewartPose(stewart); stewart = initializeInertialSensor(stewart, 'type', 'accelerometer', 'freq', 5e3); --
ground = initializeGround('type', 'rigid'); +% Ground and Payload +ground = initializeGround('type', 'rigid'); payload = initializePayload('type', 'none'); -controller = initializeController('type', 'open-loop'); --
disturbances = initializeDisturbances(); +% Controller +controller = initializeController('type', 'open-loop'); + +% Disturbances and References +disturbances = initializeDisturbances(); references = initializeReferences(stewart);
Let’s identify the transfer function from \(\bm{\tau}\) to \(\bm{L}\). @@ -1348,31 +1408,31 @@ Gl.OutputName = {'L1',
-The diagonal elements of the plant are shown in Figure 23 while the off diagonal terms are shown in Figure 24. +The diagonal elements of the plant are shown in Figure 24 while the off diagonal terms are shown in Figure 25.
We apply a decentralized (diagonal) direct velocity feedback. @@ -1382,7 +1442,7 @@ The gain of the controller is chosen such that the resonances are critically dam
-The obtain loop gain is shown in Figure 25. +The obtain loop gain is shown in Figure 26.
Kx = tf(zeros(6)); @@ -1432,8 +1492,8 @@ G.OutputName = {'Dx', '
The controller consists of: @@ -1483,7 +1543,7 @@ Kx = Kx.*diag(1./dia
-
Figure 27: Obtained Loop Gain for the controller \(\bm{K}_\mathcal{X}\) (png, pdf)
+Figure 28: Obtained Loop Gain for the controller \(\bm{K}_\mathcal{X}\) (png, pdf)
@@ -1504,11 +1564,13 @@ Then we include the Jacobian in the controller matrix. We specify the reference path to follow.
t = linspace(0, 10, 10000); +t = [0:1e-4:10]; r = zeros(6, length(t)); -r(1, :) = 5e-3*sin(2*pi*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);@@ -1518,33 +1580,59 @@ references = initializeReferences(stewart, 't', We run the simulation and we save the results.-sim('stewart_platform_model') +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 28. +The obtained position error is shown in Figure 29.
Created: 2020-03-12 jeu. 18:06
+Created: 2020-03-13 ven. 13:12