Changes between Initial Version and Version 1 of WAM/KinematicsJointRangesConversionFactors


Ignore:
Timestamp:
May 13, 2011, 2:25:46 PM (14 years ago)
Author:
edison
Comment:

--

Legend:

Unmodified
Added
Removed
Modified
  • WAM/KinematicsJointRangesConversionFactors

    v1 v1  
     1= Kinematics, Transmission Ratios, and Joint Ranges =
     2
     3== 4 DOF and 7 DOF ==
     4A 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.
     5
     6{{{
     7#!div class="center" align="center"
     8[[Image(htdocs:wam/figure35.png)]]
     9
     10'''Figure 35 – WAM 4-DOF dimensions and D-H frames'''
     11}}}
     12
     13Figure 35 shows the 4-DOF WAM system in the zero position. A positive joint motion is based on the right hand rule for each axis. Figure 37 through Figure 40 on the following pages show explicitly each of the four joint kinematic parameters and joint limits.
     14
     15{{{
     16#!div class="center" align="center"
     17[[Image(htdocs:wam/figure36.png)]]
     18
     19'''Figure 36 – WAM 7-DOF dimensions and D-H frames'''
     20}}}
     21Figure 36 shows the entire 7-DOF WAM system in the zero position. A positive joint motion is based on the right hand rule for each axis. Figure 37 through
     22Figure 43 on the following pages show explicitly each of the seven joint kinematic parameters and joint limits.
     23
     24{{{
     25#!div class="center" align="center"
     26[[Image(htdocs:wam/figure37.png)]]
     27
     28'''Figure 37: WAM Arm Joint 1 Frames and Limits'''
     29
     30[[Image(htdocs:wam/figure38.png)]]
     31
     32'''Figure 38: WAM Arm Joint 2 Frames and Limits'''
     33
     34[[Image(htdocs:wam/figure39.png)]]
     35
     36'''Figure 39: WAM Arm Joint 3 Frames and Limits'''
     37
     38[[Image(htdocs:wam/figure40.png)]]
     39
     40'''Figure 40: WAM Arm Joint 4 Frames and Limits'''
     41
     42[[Image(htdocs:wam/figure41.png)]]
     43
     44'''Figure 41: WAM Arm Joint 5 Frames and Limits'''
     45
     46[[Image(htdocs:wam/figure42.png)]]
     47
     48'''Figure 42: WAM Arm Joint 6 Frames and Limits'''
     49
     50[[Image(htdocs:wam/figure43.png)]]
     51
     52'''Figure 43: WAM Arm Joint 7 Frames and Limits'''
     53}}}
     54Equation 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 4 below. Note that c and s stand for cos and sin respectively.
     55
     56{{{
     57#!div class="center" align="center"
     58{{{
     59#!latex
     60$^{i-l}T_{i}=\left[\begin{array}{cccc}
     61c\theta_{i} & -s\theta_{i}c\alpha_{i} & s\theta_{i}s\alpha_{i} & a_{i}c\theta_{i}\\
     62s\theta_{i} & c\theta_{i}c\alpha_{i} & -c\theta_{i}s\alpha_{i} & a_{i}s\theta_{i}\\
     630 & s\alpha_{i} & c\alpha_{i} & d_{i}\\
     640 & 0 & 0 & 1\end{array}\right]$
     65}}}
     66
     67'''Equation 1: D-H generalized transform matrix'''
     68
     69'''Table 4: 4-DOF WAM frame parameters (with blank outer link installed) and 7-DOF WAM frame parameters'''
     70||i||a,,i,,||α,,i,,||d,,i,,||θ,,i,,||||||i||a,,i,,||α,,i,,||d,,i,,||θ,,i,,||
     71||1||0||−π/2||0||θ,,1,,||||||1||0||−π/2||0||θ,,1,,||
     72||2||0||π/2||0||θ,,2,,||||||2||0||π/2||0||θ,,2,,||
     73||3||0.045||−π/2||0.55||θ,,3,,||||||3||0.045||−π/2||0.55||θ,,3,,||
     74||4||−0.045||π/2||0||θ,,4,,||||||4||−0.045||π/2||0||θ,,4,,||
     75||Τ||0||0||0.35||||||||5||0||−π/2||0.3||θ,,5,,||
     76||||||||||||||||6||0||π/2||0||θ,,6,,||
     77||||||||||||||||7||0||0||0.06||θ,,7,,||
     78||||||||||||||||Τ||0||0||0||   
     79}}}
     80
     81For 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 4 as follows:
     82
     83{{{
     84#!div class="center" align="center"
     85{{{
     86#!latex
     87$^{1}T_{2}=\left[\begin{array}{cccc}
     88cos(\theta_{2}) & -sin(\theta_{2})cos(\pi/2) & sin(\theta_{2})sin(\pi/2) & cos(\theta_{2})(0)\\
     89sin(\theta_{2}) & cos(\theta_{2})cos(\pi/2) & -cos(\theta_{2})sin(\pi/2) & sin(\theta_{2})(0)\\
     900 & sin(\pi/2) & cos(\pi/2) & (0)\\
     910 & 0 & 0 & 1\end{array}\right]$
     92
     93$^{1}T_{2}=\left[\begin{array}{cccc}
     94cos(\theta_{2}) & 0 & sin(\theta_{2}) & 0\\
     95sin(\theta_{2}) & 0 & -cos(\theta_{2}) & 0\\
     960 & 1 & 0 & 0\\
     970 & 0 & 0 & 1\end{array}\right]$
     98}}}
     99 
     100'''Equation 2: D-H Matrix Example'''
     101}}}
     102
     103Each of the joints has a mechanical stop that limits the motion. Refer to Table 6 below for a complete listing of the joint limits for each axis.
     104
     105{{{
     106#!div class="center" align="center"
     107'''Table 6: Joint Limits'''
     108||Joint||Positive Joint Limit Rad (deg)||Negative Joint Limit Rad (deg)
     109||1||2.6 (150)||-2.6 (-150)
     110||2||2.0 (113)||-2.0 (-113)
     111||3||2.8 (157)||-2.8 (-157)
     112||4||3.1 (180)||-0.9 (-50)
     113||5||1.24 (71)||-4.76 (-273)
     114||6||1.6 (90)||-1.6 (-90)
     115||7||3.0 (172)||-3.0 (-172)
     116}}}
     117
     118'''Forward Kinematics for the 4-DOF WAM'''
     119
     120The forward kinematics of the 4-DOF WAM system is used to determine the end tip location and orientation. These transformations are generated using the parameters in Table 4 on page 64 and the matrix in Equation 1 on page 64.
     121
     122{{{
     123#!div class="center" align="center"
     124{{{
     125#!latex
     126$^{4}T_{tool}=\left[\begin{array}{cccc}
     127u_{x} & v_{x} & w_{x} & P_{x}\\
     128u_{y} & v_{y} & w_{y} & P_{y}\\
     129u_{z} & v_{z} & w_{z} & P_{z}\\
     1300 & 0 & 0 & 1\end{array}\right]$
     131}}}
     132 
     133'''Equation 3: Tool frame matrix'''
     134}}}
     135
     136You define the   frame for your specific end-effector. 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 tool end tip location and orientation use the following equation:
     137
     138{{{
     139#!div class="center" align="center"
     140{{{
     141#!latex
     142$^{0}T_{Tool}=^{0}T_{1}^{1}T_{2}^{2}T_{3}^{3}T_{4}^{4}T_{Tool}$
     143}}}
     144 
     145'''Equation 4: Tool end tip position and orientation equation for the 4-DOF WAM'''
     146}}}
     147
     148'''Forward Kinematics for the 7-DOF WAM'''
     149
     150As with the previous example, you define the   frame for your specific end-effector. 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 end tip location and orientation use the following equation:
     151
     152{{{
     153#!div class="center" align="center"
     154{{{
     155#!latex
     156$^{0}T_{Tool}=^{0}T_{1}^{1}T_{2}^{2}T_{3}^{3}T_{4}^{4}T_{5}^{5}T_{6}^{6}T_{7}^{7}T_{Tool}$
     157}}}
     158 
     159'''Equation 5: Tool end tip position and orientation equation for the 7-DOF WAM'''
     160}}}
     161
     162=== 4 DOF with Gimbals ===
     163A 4-DOF WAM Arm can be outfitted with optional 3-axis non-motorized gimbals that give precise angular feedback. The kinematics of the first 4 joints is identical to a 4-DOF WAM Arm. The kinematics for the additional 3 axes is shown in Figure 44.
     164
     165{{{
     166#!div class="center" align="center"
     167[[Image(htdocs:wam/figure44.png)]]
     168
     169'''Figure 44: Denavit-Hartenberg Frames – 4-DOF + Gimbals'''
     170}}}
     171
     172Figure 44 shows the WAM Gimbals in the zero position. A positive joint motion is based on the right hand rule for each axis. The D-H parameters that were derived from Figure 44 are located in Table 7 below.
     173
     174{{{
     175#!div class="center" align="center"
     176'''Table 7: 4-DOF WAM + Gimbals DH Parameters'''
     177||i||a,,i,,||α,,i,,||d,,i,,||θ,,i,,
     178||1||0||-π/2||0||θ,,1,,
     179||2||0||π/2||0||θ,,2,,
     180||3||0.045||-π/2||0.55||θ,,3,,
     181||4||0.4||-π/2||0||θ,,4,,
     182||5||0||π/2||0||θ,,5,,-π/2
     183||6||0||-π/2||0.155||θ,,6,,-π/2
     184||7||0||0||0||θ,,7,,
     185}}}
     186
     187== Motor-to-Joint Transformations ==
     188'''Motor-to-Joint Position Transformations'''
     189
     190The 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.
     191
     192{{{
     193#!div class="center" align="center"
     194'''Table 8: Arm Transmission Ratios'''
     195||Parameter||Value
     196||N,,1,,||42.0
     197||N,,2,,||28.25
     198||N,,3,,||28.25
     199||n,,3,,||1.68
     200||N,,4,,||18.0
     201||N,,5,,||9.48
     202||N,,6,,||9.48
     203||N,,7,,||14.93
     204||n,,6,,||1
     205
     206{{{
     207#!latex
     208$\left[\begin{array}{c}
     209J\theta_{1}\\
     210J\theta_{2}\\
     211J\theta_{3}\\
     212J\theta_{4}\end{array}\right]=\left[\begin{array}{cccc}
     213\frac{-1}{N_{1}} & 0 & 0 & 0\\
     2140 & \frac{1}{2N_{2}} & \frac{-1}{2N_{2}} & 0\\
     2150 & \frac{-n_{3}}{2N_{2}} & \frac{-n_{3}}{2N_{2}} & 0\\
     2160 & 0 & 0 & \frac{-1}{N_{4}}\end{array}\right]\left[\begin{array}{c}
     217M\theta_{1}\\
     218M\theta_{2}\\
     219M\theta_{3}\\
     220M\theta_{4}\end{array}\right]$
     221}}}
     222 
     223'''Equation 6: WAM Motor-to-Joint position transformations      '''
     224
     225{{{
     226#!latex
     227$\left[\begin{array}{c}
     228J\theta_{5}\\
     229J\theta_{6}\\
     230J\theta_{7}\end{array}\right]=\left[\begin{array}{ccc}
     231\frac{1}{2N_{5}} & \frac{1}{2N_{5}} & 0\\
     232\frac{-n_{6}}{2N_{5}} & \frac{n_{6}}{2N_{5}} & 0\\
     2330 & 0 & \frac{1}{N_{7}}\end{array}\right]\left[\begin{array}{c}
     234M\theta_{5}\\
     235M\theta_{6}\\
     236M\theta_{7}\end{array}\right]$
     237}}}
     238 
     239'''Equation 7: Wrist Motor-to-Joint position transformations'''
     240}}}
     241
     242The motor position can also be derived from joint space by taking the inverse of the multiplying matrix. For convenience, they are as follows:
     243
     244{{{
     245#!div class="center" align="center"
     246{{{
     247#!latex
     248$\left[\begin{array}{c}
     249M\theta_{1}\\
     250M\theta_{2}\\
     251M\theta_{3}\\
     252M\theta_{4}\end{array}\right]=\left[\begin{array}{cccc}
     253-N_{1} & 0 & 0 & 0\\
     2540 & N_{2} & \frac{-N_{2}}{n_{3}} & 0\\
     2550 & -N_{2} & \frac{-N_{2}}{n_{3}} & 0\\
     2560 & 0 & 0 & -N_{4}\end{array}\right]\left[\begin{array}{c}
     257J\theta_{1}\\
     258J\theta_{2}\\
     259J\theta_{3}\\
     260J\theta_{4}\end{array}\right]$
     261}}}
     262
     263'''Equation 8: Arm Joint-to-Motor position transformations      '''
     264
     265{{{
     266#!latex
     267$\left[\begin{array}{c}
     268M\theta_{5}\\
     269M\theta_{6}\\
     270M\theta_{7}\end{array}\right]=\left[\begin{array}{ccc}
     271N_{5} & \frac{-N_{5}}{n_{6}} & 0\\
     272N_{5} & \frac{N_{5}}{n_{6}} & 0\\
     2730 & 0 & -N_{7}\end{array}\right]\left[\begin{array}{c}
     274J\theta_{5}\\
     275J\theta_{6}\\
     276J\theta_{7}\end{array}\right]$
     277}}}
     278 
     279'''Equation 9: Wrist Joint-to-Motor position transformation'''
     280}}}
     281
     282'''Motor-to-Joint Torque Transformations'''
     283
     284Similar to the position transformations the following equations determine the joint torque from the motor torque:
     285
     286{{{
     287#!div class="center" align="center"
     288{{{
     289#!latex
     290$\left[\begin{array}{c}
     291J\tau_{1}\\
     292J\tau_{2}\\
     293J\tau_{3}\\
     294J\tau_{4}\end{array}\right]=\left[\begin{array}{cccc}
     295-N_{1} & 0 & 0 & 0\\
     2960 & N_{2} & -N_{2} & 0\\
     2970 & \frac{-N_{2}}{n_{3}} & \frac{-N_{2}}{n_{3}} & 0\\
     2980 & 0 & 0 & -N_{4}\end{array}\right]\left[\begin{array}{c}
     299M\tau_{1}\\
     300M\tau_{2}\\
     301M\tau_{3}\\
     302M\tau_{4}\end{array}\right]$
     303}}}
     304
     305'''Equation 10: Arm Motor-to-Joint torque transformation         '''
     306
     307{{{
     308#!latex
     309$\left[\begin{array}{c}
     310J\tau_{5}\\
     311J\tau_{6}\\
     312J\tau_{7}\end{array}\right]=\left[\begin{array}{ccc}
     313N_{5} & N_{5} & 0\\
     314\frac{-N_{5}}{n_{6}} & \frac{N_{5}}{n_{6}} & 0\\
     3150 & 0 & -N_{7}\end{array}\right]\left[\begin{array}{c}
     316M\tau_{5}\\
     317M\tau_{6}\\
     318M\tau_{7}\end{array}\right]$
     319}}}
     320
     321'''Equation 11: Wrist Motor-to-Joint transformations'''
     322}}}
     323
     324The following equations determine motor torque from the joint torque:
     325
     326{{{
     327#!div class="center" align="center"
     328{{{
     329#!latex
     330$\left[\begin{array}{c}
     331M\tau_{1}\\
     332M\tau_{2}\\
     333M\tau_{3}\\
     334M\tau_{4}\end{array}\right]=\left[\begin{array}{cccc}
     335\frac{-1}{N_{1}} & 0 & 0 & 0\\
     3360 & \frac{1}{2N_{2}} & \frac{-n_{3}}{2N_{2}} & 0\\
     3370 & \frac{-1}{2N_{2}} & \frac{-n_{3}}{2N_{2}} & 0\\
     3380 & 0 & 0 & \frac{-1}{N_{7}}\end{array}\right]\left[\begin{array}{c}
     339J\tau_{1}\\
     340J\tau_{2}\\
     341J\tau_{3}\\
     342J\tau_{4}\end{array}\right]$
     343}}}
     344 
     345'''Equation 12: Arm Joint-to-Motor torque transformations        '''
     346
     347{{{
     348#!latex
     349$\left[\begin{array}{c}
     350M\tau_{5}\\
     351M\tau_{6}\\
     352M\tau_{7}\end{array}\right]=\left[\begin{array}{ccc}
     353\frac{1}{2N_{5}} & \frac{-n_{6}}{2N_{5}} & 0\\
     354\frac{1}{2N_{5}} & \frac{n_{6}}{2N_{5}} & 0\\
     3550 & 0 & \frac{-1}{N_{7}}\end{array}\right]\left[\begin{array}{c}
     356J\tau_{5}\\
     357J\tau_{6}\\
     358J\tau_{7}\end{array}\right]$
     359}}}
     360
     361'''Equation 13: Wrist Joint-to-Motor torque transformations'''
     362}}}