where \(\boldsymbol{q}=\left[q_{1},\ldots, q_{n}\right]^{T}\). The concept of
Jacobian is to find the relationship between the
joint velocities and the end-effector linear (translational) and angular velocities. In
other words, we want to find the end-effector’s linear velocity
\(\dot{\boldsymbol{p}}_{e}\) and angular velocity
\(\boldsymbol{\omega}_{e}\) as a function of the joint velocities
\(\dot{\boldsymbol{q}}\) in the following form:
Here, the matrices \(\boldsymbol{J}_{P}(\boldsymbol{q})\) and \(\boldsymbol{J}_{O}(\boldsymbol{q})\) are called translational (linear) Jacobian and Angular Jacobian, respectively. Those matrices (Jacobians) themselves are a function of joint variable \(\boldsymbol{q}\).
In compact form, we use \(\boldsymbol{v}_{e}\) to describe the six-vector velocity of the end-effector, combining the linear and angular velocities. \(\boldsymbol{v}_{e}\) will be written as
The stacked \((6 \times n)\) matrix \(\boldsymbol{J}(\boldsymbol{q})\) is sometimes also called geometric Jacobian. And \(\boldsymbol{v}_{e}\) is often called the twist of the end-effector.
This expression shows how \(\dot{\boldsymbol{p}}_{e}\) can be obtained as
the sum of the terms \(\dot{q}_{i} \boldsymbol{J}_{P,i}\). Each \(\dot{q}_{i} \boldsymbol{J}_{P,i}\)
represents the contribution of the velocity of Joint \(i\) to the linear velocity of the
end-effector when all the other joints hold still. The following derivation is based on the previous velocity kinematics.
This expression shows how \(\dot{\boldsymbol{p}}_{e}\) can be obtained as
the sum of the terms \(\dot{q}_{i} \boldsymbol{J}_{O,i}\). Each \(\dot{q}_{i} \boldsymbol{J}_{O,i}\)
represents the contribution of the velocity of Joint \(i\) to the angular velocity of the
end-effector when all the other joints hold still. The following derivation is based on the previous velocity kinematics.
In the above (20) or (21), the vectors
\(\boldsymbol{z}_{i-1}, \boldsymbol{p}_{e}\) and \(\boldsymbol{p}_{i-1}\)
are all functions of the joint variables, and can be obtained from FK. In particular,
\(\boldsymbol{z}_{i-1}\) is given by the third column of
the rotation matrix
As you can see, the linear Jacobian remains the same as before, the only difference is the angular Jacobian \(\boldsymbol{J}_{O}(\boldsymbol{q})\) becomes
for the Euler ZYZ Angle
\({\boldsymbol{\phi}}_{e}=[{\varphi}, {\vartheta}, \psi]^T\).
Recall the rotation induced from the Euler ZYZ Angle. The angualr velocities \(\dot{\varphi}, \dot{\vartheta}, \dot\psi\) is always with respect to the current frame, as shown in Fig. 66.
Therefore, to compute \(\boldsymbol{\omega}_{e}\), we just need to first, express each Euler angle velocity \(\dot{\varphi}, \dot{\vartheta}, \dot\psi\) from its respective current from to the reference
frame, and second, sum them up!
The angular velocity corresponding to \(\dot{\varphi}\) is
Takeaway: From a physical viewpoint, the meaning of \(\omega_{e}\) is
more intuitive than that of \(\dot{\boldsymbol{\phi}}_{e}\). The three
components of \(\boldsymbol{\omega}_{e}\) represent the components of
angular velocity with respect to the base frame. Instead, the three
elements of \(\dot{\phi}_{e}\) represent nonorthogonal components of
angular velocity defined with respect to the axes of a frame that varies
as the end-effector orientation varies. On the other hand, while the
integral of \(\dot{\phi}_{e}\) over time gives \(\phi_{e}\), the integral of
\(\omega_{e}\) does not admit a clear physical interpretation, as can be
seen in the following example.