The kinematic analysis of a parallel manipulator is well described in cite:taghirad13_paral:
#+begin_quote
Kinematic analysis refers to the study of the geometry of motion of a robot, without considering the forces an torques that cause the motion.
In this analysis, the relation between the geometrical parameters of the manipulator with the final motion of the moving platform is derived and analyzed.
#+end_quote
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.
The Jacobian matrix not only reveals the *relation between the joint variable velocities of a parallel manipulator to the moving platform linear and angular velocities*, it also constructs the transformation needed to find the *actuator forces from the forces and moments acting on the moving platform*.
The Jacobian matrix $\bm{J}$ can be computed using the =computeJacobian= function (accessible [[sec:computeJacobian][here]]).
For instance:
#+begin_src matlab :eval no
stewart = computeJacobian(stewart);
#+end_src
This will add three new matrix to the =stewart= structure:
- =J= the Jacobian matrix
- =K= the stiffness matrix
- =C= the compliance matrix
** Jacobian - Velocity loop closure
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$:
The input joint rate $\dot{\bm{\mathcal{L}}}$ can be measured by taking the derivative of the relative motion sensor in each strut.
The output twist vector can be measured with a "Transform Sensor" block measuring the relative velocity and relative angular velocity of frame $\{B\}$ with respect to frame $\{A\}$.
If the Jacobian matrix is inversible, we can also compute $\dot{\bm{\mathcal{X}}}$ from $\dot{\bm{\mathcal{L}}}$.
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 $\bm{\mathcal{L}} = \left[ l_1, l_2, l_3, l_4, l_5, l_6 \right]^T$.
#+end_quote
This problem can be easily solved using the loop closures.
In *forward kinematic analysis*, it is assumed that the vector of limb lengths $\bm{L}$ is given and the problem is to find the position ${}^A\bm{P}$ and the orientation ${}^A\bm{R}_B$.
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):
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):
These two relations solve the forward and inverse kinematic problems for small displacement in a *approximate* way.
As the inverse kinematic can be easily solved exactly this is not much useful, however, as the forward kinematic problem is difficult to solve, this approximation can be very useful for small displacements.
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
*** 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.
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.
We first define some general Stewart architecture.
#+begin_src matlab
stewart = initializeFramesPositions('H', 90e-3, 'MO_B', 45e-3);
stewart = generateGeneralConfiguration(stewart);
stewart = computeJointsPose(stewart);
stewart = initializeStewartPose(stewart);
stewart = initializeCylindricalPlatforms(stewart);
stewart = initializeCylindricalStruts(stewart);
stewart = initializeStrutDynamics(stewart);
stewart = initializeJointDynamics(stewart);
stewart = computeJacobian(stewart);
#+end_src
*** 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.
The estimate required strut stroke for both the approximate and exact solutions are shown in Figure [[fig:inverse_kinematics_approx_validity_x_translation]].
The relative strut length displacement is shown in Figure [[fig:inverse_kinematics_approx_validity_x_translation_relative]].
#+begin_src matlab
Xrs = logspace(-6, -1, 100); % Wanted X translation of the mobile platform [m]
#+CAPTION: Comparison of the Approximate solution and True solution for the Inverse kinematic problem ([[./figs/inverse_kinematics_approx_validity_x_translation.png][png]], [[./figs/inverse_kinematics_approx_validity_x_translation.pdf][pdf]])
#+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]])
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.
* Estimated required actuator stroke from specified platform mobility
ans = sprintf('From %.2g[m] to %.2g[m]: Total stroke = %.1f[um]', min(min([LTx,LTy,LTz,LRx,LRy])), max(max([LTx,LTy,LTz,LRx,LRy])), 1e6*(max(max([LTx,LTy,LTz,LRx,LRy]))-min(min([LTx,LTy,LTz,LRx,LRy]))))
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=.
#+begin_src matlab
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
#+end_src
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.
#+begin_src matlab :exports results :results value table replace :tangle no :post addhdr(*this*)
#+CAPTION: Obtain mobility of the Stewart platform for zero rotations ([[./figs/mobility_translations_null_rotation.png][png]], [[./figs/mobility_translations_null_rotation.pdf][pdf]])
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$.
From the geometry of the manipulator, the loop closure for each limb, $i = 1, 2, \dots, 6$ can be written as
If the position and orientation of the moving platform lie in the feasible workspace of the manipulator, one unique solution to the limb length is determined by the above equation.
Otherwise, when the limbs' lengths derived yield complex numbers, then the position or orientation of the moving platform is not reachable.