Version 1 (modified by aj, 8 years ago) (diff)

--

Kinematics, Transmission Ratios, and Joint Ranges

4 DOF and 7 DOF

A good introduction to coordinate frames, transformations and kinematics is beyond the scope of this document. There are several good introductory robotics books available. We recommend Spong, M.; Hutchinson, S.; Vidyasagar, M. Robot Modeling and Control; 2006 John Wiley & Sons as we use the variant of the Denavit-Hartenberg (D-H) method that is from this book to establish the coordinate frames.

D-H frames are defined roughly as shown in Figure 1 when the robot is in its zero position (NOT the robot’s home position). Note that the joint range of Joint 3 (Table 2) prevents the Proficio from actually reaching this position. Frames 0 and 1 are located at the intersection of the J1 and J2 axes. Frame 2 is coincident to the J3 axis. The frame 3 origin is coincident to the center of the haptic ball when it points straight up. The D-H parameters do not change between left- and right-handed configurations. However, the configuration files do contain separate world-to-base transforms for each configuration. These transforms define the origin of the world frame to be at the user’s sternum, 540 mm from the X1-Z1 plane along Z0. The diagram shows the locations of the world origin in left-handed and right-handed robot configurations. A positive joint motion is based on the right hand rule for each axis.

DHFramesSm.PNG

Figure 1: Proficio D-H frames

Equation 1 below gives the transform between two adjacent D-H coordinate frames. The D-H parameters that were derived from this equation are located in Table 1 below. Note that c and s stand for cos and sin respectively.

$^{i-l}T_{i}=\left[\begin{array}{cccc}
c\theta_{i} & -s\theta_{i}c\alpha_{i} & s\theta_{i}s\alpha_{i} & a_{i}c\theta_{i}\\
s\theta_{i} & c\theta_{i}c\alpha_{i} & -c\theta_{i}s\alpha_{i} & a_{i}s\theta_{i}\\
0 & s\alpha_{i} & c\alpha_{i} & d_{i}\\
0 & 0 & 0 & 1\end{array}\right]$

Equation 1: D-H generalized transform matrix

Table 1: Proficio frame parameters

iaiαidiθi
10π/20θ1
20.65000.156θ2
30.435−π/20.069θ3

For example, to generate the transform from coordinate Frame 2 to coordinate Frame 1 (i.e. the position and orientation of Frame 2 described in terms of Frame 1 which is also a rotation about joint 2), use the parameters in the second row of Table 1 as follows:

$^{1}T_{2}=\left[\begin{array}{cccc}
\cos(\theta_{2}) & -\sin(\theta_{2})\cos(0) & \sin(\theta_{2})\sin(0) & 0.650\cos(\theta_{2})\\
\sin(\theta_{2}) & \cos(\theta_{2})\cos(0) & -\cos(\theta_{2})\sin(0) & 0.650\sin(\theta_{2})\\
0 & \sin(0) & \cos(0) & (0.156)\\
0 & 0 & 0 & 1\end{array}\right]$

$^{1}T_{2}=\left[\begin{array}{cccc}
\cos\theta_{2} & -\sin\theta_2 & 0 & 0.650\cos\theta_2\\
\sin\theta_{2} & \cos\theta_2 & 0 & 0.650\sin\theta_{2}\\
0 & 0 & 1 & 0.156\\
0 & 0 & 0 & 1\end{array}\right]$

Equation 2: D-H Matrix Example

Each of the joints has a mechanical stop that limits the motion. Table 2 below shows a complete listing of the joint limits for each axis. 3R and 3L correspond to joint limits for joint 3 in the right and left configurations, respectively.

Table 2: Joint Limits

JointPositive Joint Limit Rad (deg)Negative Joint Limit Rad (deg)
1+0.56 (+32)-1.01 (-58)
2+0.96 (+55)-0.96 (-55)
3R+2.84 (+163)+0.40 (+23)
3L-0.40 (-23)-2.84 (-163)

Forward Kinematics for the Proficio

The forward kinematics of the Proficio are used to determine the end tip location and orientation. These transformations are generated using the parameters in Table 1 and the matrix in Equation 1.

The forward kinematics are determined for any frame on the robot by mulitplying all of the transforms up to and including the final frame. To determine the endpoint location and orientation use the following equation:

$^{0}T_{3}=^{0}T_{1}^{1}T_{2}^{2}T_{3}^{3}$

Equation 3: Tool end tip position and orientation equation for the Proficio

Motor-to-Joint Transformations

Motor-to-Joint Position Transformations

The following transformations show the change in joint positions as a function of motor positions. The input transmission ratios and the differential transmission ratios are calculated from known pulley, pinion, and cable diameters.

Table 8: Arm Transmission Ratios

ParameterValue
N18.51
N28.51
n20.56
N39.55
$\left[\begin{array}{c}
J\theta_{1}\\
J\theta_{2}\\
J\theta_{3}\end{array}\right]=\left[\begin{array}{cccc}
-1/2N_1 & 1/2N_2 & 0\\
n_2/2N_1 & n_2/2N_1 & 0\\
0 & 0 & 1/N_3\end{array}\right]\left[\begin{array}{c}
M\theta_{1}\\
M\theta_{2}\\
M\theta_{3}\end{array}\right]$

Equation 6: WAM Motor-to-Joint position transformations

The motor position can also be derived from joint space by taking the inverse of the multiplying matrix. For convenience, they are as follows:

$\left[\begin{array}{c}
M\theta_{1}\\
M\theta_{2}\\
M\theta_{3}
\end{array}\right]=\left[\begin{array}{cccc}
-N_{1} & N_1/n_2 & 0\\
N_{1} & N_2/n_2 & 0\\
0 & 0 & N_3\end{array}\right]\left[\begin{array}{c}
J\theta_{1}\\
J\theta_{2}\\
J\theta_{3}\end{array}\right]$

Equation 8: Arm Joint-to-Motor position transformations

Motor-to-Joint Torque Transformations

Similar to the position transformations the following equations determine the joint torque from the motor torque:

$\left[\begin{array}{c}
J\tau_{1}\\
J\tau_{2}\\
J\tau_{3}\end{array}\right]=\left[\begin{array}{cccc}
-N_1 & N_2 & 0\\
N_1/n_2 & N_2/n_2 & 0\\
0 & 0 & N_3\end{array}\right]\left[\begin{array}{c}
M\tau_{1}\\
M\tau_{2}\\
M\tau_{3}\end{array}\right]$

Equation 10: Arm Motor-to-Joint torque transformation

The following equations determine motor torque from the joint torque:

$\left[\begin{array}{c}
M\tau_{1}\\
M\tau_{2}\\
M\tau_{3}\end{array}\right]=\left[\begin{array}{cccc}
-1/2N_1 & n_2/2N_1 & 0\\
1/2N_2 & n_2/2N_2 & 0\\
0 & 0 & 1/N_3\end{array}\right]\left[\begin{array}{c}
J\tau_{1}\\
J\tau_{2}\\
J\tau_{3}\end{array}\right]$

Equation 12: Arm Joint-to-Motor torque transformations