diff --git a/figs/mobility_translations_null_rotation.pdf b/figs/mobility_translations_null_rotation.pdf new file mode 100644 index 0000000..5a73f72 Binary files /dev/null and b/figs/mobility_translations_null_rotation.pdf differ diff --git a/figs/mobility_translations_null_rotation.png b/figs/mobility_translations_null_rotation.png new file mode 100644 index 0000000..34b10ef Binary files /dev/null and b/figs/mobility_translations_null_rotation.png differ diff --git a/kinematic-study.html b/kinematic-study.html index 13c094a..c8c8256 100644 --- a/kinematic-study.html +++ b/kinematic-study.html @@ -4,7 +4,7 @@ "http://www.w3.org/TR/xhtml1/DTD/xhtml1-strict.dtd">
- +computeJacobian
: Compute the Jacobian Matrix
+computeJacobian
: Compute the Jacobian Matrix
inverseKinematics
: Compute Inverse Kinematics
+inverseKinematics
: Compute Inverse Kinematics
forwardKinematicsApprox
: Compute the Approximate Forward Kinematics
+forwardKinematicsApprox
: Compute the Approximate Forward Kinematics
From taghirad13_paral: @@ -373,8 +374,8 @@ The Jacobian matrix not only reveals the relation between the joint variable
If we note: @@ -399,7 +400,7 @@ Then, we can compute the Jacobian with the following equation (the superscript \ \end{equation*}
-The Jacobian matrix \(\bm{J}\) can be computed using the computeJacobian
function (accessible here).
+The Jacobian matrix \(\bm{J}\) can be computed using the computeJacobian
function (accessible here).
For instance:
stewart
structure:
The Jacobian matrix links the input joint rate \(\dot{\bm{\mathcal{L}}} = [ \dot{l}_1, \dot{l}_2, \dot{l}_3, \dot{l}_4, \dot{l}_5, \dot{l}_6 ]^T\) of each strut to the output twist vector of the mobile platform is denoted by \(\dot{\bm{X}} = [^A\bm{v}_p, {}^A\bm{\omega}]^T\): @@ -441,13 +442,13 @@ If the Jacobian matrix is inversible, we can also compute \(\dot{\bm{\mathcal{X}
The Jacobian matrix can also be used to approximate forward and inverse kinematics for small displacements. -This is explained in section 3.3. +This is explained in section 3.3.
If we note: @@ -474,19 +475,19 @@ If the Jacobian matrix is inversible, we also have the following relation:
Here, we focus on the deflections of the manipulator moving platform that are the result of the external applied wrench to the mobile platform. The amount of these deflections are a function of the applied wrench as well as the manipulator structural stiffness.
As explain in this document, each Actuator is modeled by 3 elements in parallel: @@ -537,24 +538,24 @@ The compliance matrix of a manipulator shows the mapping of the moving platform \end{equation*}
-The stiffness and compliance matrices are computed using the computeJacobian
function (accessible here).
+The stiffness and compliance matrices are computed using the computeJacobian
function (accessible here).
-For small displacements mobile platform displacement \(\delta \bm{\mathcal{X}} = [\delta x, \delta y, \delta z, \delta \theta_x, \delta \theta_y, \delta \theta_z ]^T\) around \(\bm{\mathcal{X}}_0\), the associated joint displacement can be computed using the Jacobian: +For small displacements mobile platform displacement \(\delta \bm{\mathcal{X}} = [\delta x, \delta y, \delta z, \delta \theta_x, \delta \theta_y, \delta \theta_z ]^T\) around \(\bm{\mathcal{X}}_0\), the associated joint displacement can be computed using the Jacobian (approximate solution of the inverse kinematic problem):
\begin{equation*} \delta\bm{\mathcal{L}} = \bm{J} \delta\bm{\mathcal{X}} \end{equation*}-Similarly, for small joint displacements \(\delta\bm{\mathcal{L}} = [ \delta l_1,\ \dots,\ \delta l_6 ]^T\) around \(\bm{\mathcal{L}}_0\), it is possible to find the induced small displacement of the mobile platform: +Similarly, for small joint displacements \(\delta\bm{\mathcal{L}} = [ \delta l_1,\ \dots,\ \delta l_6 ]^T\) around \(\bm{\mathcal{L}}_0\), it is possible to find the induced small displacement of the mobile platform (approximate solution of the forward kinematic problem):
\begin{equation*} \delta\bm{\mathcal{X}} = \bm{J}^{-1} \delta\bm{\mathcal{L}} @@ -638,13 +639,13 @@ As the inverse kinematic can be easily solved exactly this is not much useful, h
-The function forwardKinematicsApprox
(described here) can be used to solve the forward kinematic problem using the Jacobian matrix.
+The function forwardKinematicsApprox
(described here) can be used to solve the forward kinematic problem using the Jacobian matrix.
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. @@ -658,8 +659,8 @@ This will also gives us the range for which the approximate forward kinematic is
We first define some general Stewart architecture. @@ -679,8 +680,8 @@ stewart = computeJacobian(stewart);
Let’s first compare the perfect and approximate solution of the inverse for pure \(x\) translations. @@ -688,8 +689,8 @@ Let’s first compare the perfect and approximate solution of the inverse fo
We compute the approximate and exact required strut stroke to have the wanted mobile platform \(x\) displacement. -The estimate required strut stroke for both the approximate and exact solutions are shown in Figure 1. -The relative strut length displacement is shown in Figure 2. +The estimate required strut stroke for both the approximate and exact solutions are shown in Figure 1. +The relative strut length displacement is shown in Figure 2.
Xrs = logspace(-6, -1, 100); % Wanted X translation of the mobile platform [m] @@ -706,14 +707,14 @@ Ls_exact = zeros(6, length(Xrs));
Figure 1: Comparison of the Approximate solution and True solution for the Inverse kinematic problem (png, pdf)
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. @@ -732,11 +733,11 @@ For small wanted displacements (up to \(\approx 1\%\) of the size of the Hexapod
Let’s say one want to design a Stewart platform with some specified mobility (position and orientation). @@ -744,8 +745,8 @@ One may want to determine the required actuator stroke required to obtain the sp This is what is analyzed in this section.
Let’s first define the Stewart platform architecture that we want to study. @@ -765,8 +766,8 @@ stewart = computeJacobian(stewart);
Let’s now define the wanted extreme translations and rotations. @@ -783,8 +784,8 @@ Rz_max = 0; % Rotation [rad]
As a first estimation, we estimate the needed actuator stroke for “pure” rotations and translation. @@ -815,8 +816,8 @@ This is surely a low estimation of the required stroke.
We know would like to have a more precise estimation. @@ -1136,23 +1137,23 @@ This is probably a much realistic estimation of the required actuator stroke.
Here, from some value of the actuator stroke, we would like to estimate the mobility of the Stewart platform.
-As explained in section 3, the forward kinematic problem of the Stewart platform is quite difficult to solve. +As explained in section 3, the forward kinematic problem of the Stewart platform is quite difficult to solve. However, for small displacements, we can use the Jacobian as an approximate solution.
Let’s first define the Stewart platform architecture that we want to study. @@ -1181,23 +1182,100 @@ L_max = 50e-6; % [m]
+Let’s first estimate the mobility in translation when the orientation of the Stewart platform stays the same. +
+ ++As shown previously, for such small stroke, we can use the approximate Forward Dynamics solution using the Jacobian matrix: +
+\begin{equation*} + \delta\bm{\mathcal{L}} = \bm{J} \delta\bm{\mathcal{X}} +\end{equation*} + ++To obtain the mobility “volume” attainable by the Stewart platform when it’s orientation is set to zero, we use the spherical coordinate \((r, \theta, \phi)\). +
+ +
+For each possible value of \((\theta, \phi)\), we compute the maximum radius \(r\) attainable with the constraint that the stroke of each actuator should be between L_min
and L_max
.
+
thetas = linspace(0, pi, 50); +phis = linspace(0, 2*pi, 50); +rs = zeros(length(thetas), length(phis)); + +for i = 1:length(thetas) + for j = 1:length(phis) + Tx = sin(thetas(i))*cos(phis(j)); + Ty = sin(thetas(i))*sin(phis(j)); + Tz = cos(thetas(i)); + + dL = stewart.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 +end ++
+Now that we have found the corresponding radius \(r\), we plot the obtained mobility. +We can also approximate the mobility by a sphere with a radius equal to the minimum obtained value of \(r\), this is however a pessimistic estimation of the mobility. +
+ +L_min [\(\mu m\)] |
+L_max [\(\mu m\)] |
+R [\(\mu m\)] |
+
---|---|---|
-50.0 | +50.0 | +31.5 | +
computeJacobian
: Compute the Jacobian MatrixcomputeJacobian
: Compute the Jacobian Matrix@@ -1205,9 +1283,9 @@ This Matlab function is accessible here.
function [stewart] = computeJacobian(stewart) % computeJacobian - @@ -1229,9 +1307,9 @@ This Matlab function is accessible here.
stewart.J = [stewart.As' , cross(stewart.Ab, stewart.As)'];@@ -1239,9 +1317,9 @@ This Matlab function is accessible here.
stewart.K = stewart.J'*diag(stewart.Ki)*stewart.J;@@ -1249,9 +1327,9 @@ This Matlab function is accessible here.
stewart.C = inv(stewart.K);@@ -1260,11 +1338,11 @@ This Matlab function is accessible here.
inverseKinematics
: Compute Inverse KinematicsinverseKinematics
: Compute Inverse Kinematics@@ -1272,9 +1350,9 @@ This Matlab function is accessible here.
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} @@ -1297,9 +1375,9 @@ This Matlab function is accessible here.
arguments stewart @@ -1311,9 +1389,9 @@ This Matlab function is accessible here.
For inverse kinematic analysis, it is assumed that the position \({}^A\bm{P}\) and orientation of the moving platform \({}^A\bm{R}_B\) are given and the problem is to obtain the joint variables, namely, \(\bm{L} = [l_1, l_2, \dots, l_6]^T\).
@@ -1347,9 +1425,9 @@ Otherwise, when the limbs’ lengths derived yield complex numbers, then theLi = sqrt(args.AP'*args.AP + diag(stewart.Bb'*stewart.Bb) + diag(stewart.Aa'*stewart.Aa) - (2*args.AP'*stewart.Aa)' + (2*args.AP'*(args.ARB*stewart.Bb))' - diag(2*(args.ARB*stewart.Bb)'*stewart.Aa));@@ -1363,11 +1441,11 @@ Otherwise, when the limbs’ lengths derived yield complex numbers, then the
forwardKinematicsApprox
: Compute the Approximate Forward KinematicsforwardKinematicsApprox
: Compute the Approximate Forward Kinematics@@ -1375,9 +1453,9 @@ This Matlab function is accessible here<
function [P, R] = forwardKinematicsApprox(stewart, args) % forwardKinematicsApprox - Computed the approximate pose of {B} with respect to {A} from the length of each strut and using @@ -1399,9 +1477,9 @@ This Matlab function is accessible here<
arguments stewart @@ -1412,9 +1490,9 @@ This Matlab function is accessible here<
From a small displacement of each strut \(d\bm{\mathcal{L}}\), we can compute the position and orientation of {B} with respect to {A} using the following formula: @@ -1465,7 +1543,7 @@ We then compute the corresponding rotation matrix.
Created: 2020-01-29 mer. 17:48
+Created: 2020-01-29 mer. 20:22