Robot Jacobian expressed in end effector frame

A Jacobian is a vector derivative with respect to another vector. If we have a vector valued function of a vector of variables $ f(x)$ , the Jacobian is a matrix of partial derivatives where there exist one partial derivative for each combination of components of the vectors. The Jacobian matrix contains all of the information necessary to relate a change in any component of $ x$ to a change in any component of $ f$ . The Jacobian is usually written as $ J(f,x)$ .

$\displaystyle J(f,x) = \frac{dx}{dy} = 
 \begin{bmatrix}
 \frac{\partial f_{1}}...
...}} & \cdots & \cdots & \frac{\partial f_{M}}{\partial x_{N}}  
 \end{bmatrix}$(22)

The following section will explain in detail how the Jacobian matrix is computed and finally the entire Jacobian matrix for the 5-DOF robotic arm is computed. Consider a simple 2D robot arm with two 1-DOF rotational joints:
Figure 7: 2D robot arm with two 1-DOF rotational joints
Image j1

The Jacobian matrix $ J(e,\Phi)$ shows how each component of $ e$ varies with respect to each joint angle. Here $ e$ is a point on the end effector and $ \Phi$ is the joint angle. $ e_{x}$ and $ e_{y}$ are the components of $ e$ in the 2D plane.

$\displaystyle J(e,\Phi) =
 \begin{bmatrix}
 \frac{\partial e_{x}}{\partial \phi...
...\partial \phi_{1}} & \frac{\partial e_{y}}{\partial \phi_{2}} 
 \end{bmatrix}$(23)

Jacobian matrix can be determined either by differentiation of the forward kinematics equation or by iterative recursive equation[ 31]. The iterative recursive equation describes a relationship between joint angle rate of change $ (\dot{\theta})$ and the translational and rotational velocities of the end effector $ (\dot{X})$ which is expressed as,

$\displaystyle {}^N\!\dot{X} = {}^N\!J(\theta)\dot{\theta}$(24)

The above equation can be expanded to,

$\displaystyle {}^N\!\dot{X} = \begin{bmatrix}{}^N\!v_{N} {}^N\!\omega_{N}\end...
...\dot{\theta_{1}} \dot{\theta_{2}} \cdots \dot{\theta_{N}} \end{bmatrix}$(25)

The linear translational and rotational velocity can be iteratively computed as follows,

$\displaystyle {}^{i+1}\!\omega_{i+1} = ({}^{i+1}\!_{i}R)({}^{i}\!\omega_{i})+ \begin{bmatrix}0 0 \dot{\theta}_{i+1} \end{bmatrix}$(26)

$\displaystyle {}^{i+1}\!v_{i+1} = ({}^{i+1}\!_{i}R)({}^{i}\!\omega \times {}^{i}\!P_{i+1} + {}^{i}\!v_{i}) + \begin{bmatrix}0 0 \dot{d}_{i+1} \end{bmatrix}$(27)

In the above equation $ {}^{i+1}\!_{i}R$ and $ {}^{i}\!P_{i+1}$ are the rotation and translation parameters related to adjacent joints and this can be calculated by assigning coordinate frames to each joints as mentioned in [31]. Denavit-Hartenberg parameters, link length ($ a_i$ ) , link twist ($ \alpha_i$ ) and link offset ($ d_i$ ) which are constant geometric quantities, are identified for each joint, after the coordinate frame assignment. A homogeneous transformation matrix $ T_i$ which refers the position and orientation of the $ (i)^{th}$ frame to the position and orientation of the $ (i-1)^{th}$ frame can be calculated from the D-H parameters and following generalized matrix form,

$\displaystyle {}^{i-1}\!_{i}T = 
 \begin{bmatrix}
 c\theta_i & -s\theta_i & 0 &...
...ha_{i-1} & c\alpha_{i-1} & c\alpha_{i-1}d_i 
 0 & 0 & 0 & 1 
 \end{bmatrix}$(28)

Where $ c\theta_i = cos \theta_i$ , $ s\theta_i= sin \theta_i$ and $ \theta_i$ is the joint angle between the two joint axis. In this homogeneous transformation matrix upper left $ 3 \times 3$ matrix refer to the rotation which constitutes of two parts. One, ( $ Rot(z,\theta_i)$ ) is due to the rotation of joint axis and the other,( $ Rot(x,\alpha_i)$ ) due to link twist. The right $ 1 \times 4$ matrix refer to the translation part whose components are link length $ a_i$ and link offset $ d_i$ .
Rotation and translation parameters for each joint required in equations ( 26) and ( 27) can be obtained from this homogeneous transformation matrix and Jacobian matrix can be expressed stacking the result for all joints.
Following is the image of the robot arm under consideration whose coordinate frames are assigned for all joints.
Figure 8: Robot arm with coordinate frames assigned to each joints.
Image Image5

The D-H parameters can be expressed as,

Table 2: D-H Parameters
$ i$$ \alpha_{i-1}$$ a_{i-1}$$ d_i$$ \theta_i$
$ 1$000$ \theta_1$
$ 2$$ 90$$ l1$0$ \theta_2$
$ 3$$ 90$$ l2$$ d1$$ \theta_3$
$ 4$$ 90$$ l3$0$ \theta_4$
$ 5$0$ l4$0$ \theta_5$
$ 6$0$ l5$00




The Jacobian matrix calculated using iterative recursive estimation is as follows. The complete calculation steps are given in the appendix.

$\displaystyle J(\theta)=
 \begin{bmatrix}
 j_{11} & j_{12} & 0 & j_{14} & 0 
...
...51} & j_{52} & j_{53} & 0 & 0 
 j_{61} & j_{62} & 0 & 1 & 1 
 \end{bmatrix}$(29)

$\displaystyle \begin{tabular}{l l l}
 $j_{11}$ & = & (s5s4s3 - c5c4s3)$l_1$ +...
...3 
 $j_{63}$& = & 0 
 $j_{64}$& = & 1 
 $j_{65}$& = & 1 
 \end{tabular}$ 



Where, l1, l2 l3, l4, l5 are link lengths, d1 is the link offset at $ 3^rd$ joint,
$ \theta_1$ , $ \theta_2$ , $ \theta_3$ , $ \theta_4$ , $ \theta_5$ are joint angles,
s1,s2,s3,s4,s5 corresponds to sine $ \theta_1$ , sine $ \theta_2$ , sine $ \theta_3$ , sine $ \theta_4$ , sine $ \theta_5$ ,
c1,c2,c3,c4,c5 corresponds to cosine $ \theta_1$ , cosine $ \theta_2$ , cosine $ \theta_3$ , cosine $ \theta_4$ , cosine $ \theta_5$ .
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值