|
| 1 | +#!/usr/bin/env python |
| 2 | +""" |
| 3 | +@author: Peter Corke |
| 4 | +""" |
| 5 | + |
| 6 | +# Note:: |
| 7 | +# - SI units are used. |
| 8 | +# - Gear ratios not currently known, though reflected armature inertia |
| 9 | +# is known, so gear ratios are set to 1. |
| 10 | +# |
| 11 | +# References:: |
| 12 | +# - Kinematic data from "Modelling, Trajectory calculation and Servoing of |
| 13 | +# a computer controlled arm". Stanford AIM-177. Figure 2.3 |
| 14 | +# - Dynamic data from "Robot manipulators: mathematics, programming and control" |
| 15 | +# Paul 1981, Tables 6.5, 6.6 |
| 16 | +# - Dobrotin & Scheinman, "Design of a computer controlled manipulator for |
| 17 | +# robot research", IJCAI, 1973. |
| 18 | + |
| 19 | +# all parameters are in SI units: m, radians, kg, kg.m2, N.m, N.m.s etc. |
| 20 | + |
| 21 | +from roboticstoolbox import SerialLink |
| 22 | +from roboticstoolbox import Revolute, Prismatic |
| 23 | +from math import pi |
| 24 | +import numpy as np |
| 25 | + |
| 26 | + |
| 27 | +class Stanford(SerialLink): |
| 28 | + """ |
| 29 | + Create model of Stanford arm manipulator |
| 30 | +
|
| 31 | + puma = Puma560() is a script which creates a puma SerialLink object |
| 32 | + describing the kinematic and dynamic characteristics of a Unimation Puma |
| 33 | + 560 manipulator using standard DH conventions. |
| 34 | +
|
| 35 | + Also define some joint configurations: |
| 36 | + - qz, zero joint angle configuration, 'L' shaped configuration |
| 37 | + - qr, vertical 'READY' configuration |
| 38 | + - qs, arm is stretched out in the X direction |
| 39 | + - qn, arm is at a nominal non-singular configuration |
| 40 | +
|
| 41 | +
|
| 42 | +
|
| 43 | + """ |
| 44 | + |
| 45 | + def __init__(self): |
| 46 | + |
| 47 | + deg = pi/180 |
| 48 | + inch = 0.0254 |
| 49 | + |
| 50 | + L0 = Revolute( |
| 51 | + d=0.412, # link length (Dennavit-Hartenberg notation) |
| 52 | + a=0, # link offset (Dennavit-Hartenberg notation) |
| 53 | + alpha=-pi/2, # link twist (Dennavit-Hartenberg notation) |
| 54 | + I=[0.276, 0.255, 0.071, 0, 0, 0], # inertia tensor of link with respect to |
| 55 | + # center of mass I = [L_xx, L_yy, L_zz, |
| 56 | + # L_xy, L_yz, L_xz] |
| 57 | + r=[0, 0.0175, -0.1105], # distance of ith origin to center of mass [x,y,z] |
| 58 | + # in link reference frame |
| 59 | + m=9.29, # mass of link |
| 60 | + Jm=0.953, # actuator inertia |
| 61 | + G=1, # gear ratio |
| 62 | + qlim=[-170*deg, 170*deg]) # minimum and maximum joint angle |
| 63 | + |
| 64 | + L1 = Revolute( |
| 65 | + d=0.154, a=0., alpha=pi/2, |
| 66 | + I=[0.108, 0.018, 0.100, 0, 0, 0], |
| 67 | + r=[0, -1.054, 0], |
| 68 | + m=5.01, Jm=2.193, G=1, |
| 69 | + qlim=[-170*deg, 170*deg]) |
| 70 | + |
| 71 | + L2 = Prismatic( |
| 72 | + theta=-pi/2, a=0.0203, alpha=0, |
| 73 | + I=[2.51, 2.51, 0.006, 0, 0, 0], |
| 74 | + r=[0, 0, -6.447], |
| 75 | + m=4.25, Jm=0.782, G=1, |
| 76 | + qlim=[12*inch, (12+38)*inch]) |
| 77 | + |
| 78 | + L3 = Revolute( |
| 79 | + d=0, a=0, alpha=-pi/2, |
| 80 | + I=[0.002, 0.001, 0.001, 0, 0, 0], |
| 81 | + r=[0, 0.092, -0.054], |
| 82 | + m=1.08, Jm=0.106, G=1, |
| 83 | + qlim=[-170*deg, 170*deg]) |
| 84 | + |
| 85 | + L4 = Revolute( |
| 86 | + d=0, a=0, alpha=pi/2, |
| 87 | + I=[0.003, 0.0004, 0, 0, 0, 0], |
| 88 | + r=[0, 0.566, 0.003], m=0.630, |
| 89 | + Jm=0.097, G=1, |
| 90 | + qlim=[-90*deg, 90*deg]) |
| 91 | + |
| 92 | + L5 = Revolute( |
| 93 | + d=0, a=0, alpha=0, |
| 94 | + I=[0.013, 0.013, 0.0003, 0, 0, 0], |
| 95 | + r=[0, 0, 1.554], m=0.51, Jm=0.020, |
| 96 | + G=1, |
| 97 | + qlim=[-170*deg, 170*deg]) |
| 98 | + |
| 99 | + L = [L0, L1, L2, L3, L4, L5] |
| 100 | + |
| 101 | + # zero angles, L shaped pose |
| 102 | + self._qz = np.array([0, 0, 0, 0, 0, 0]) |
| 103 | + |
| 104 | + super(Stanford, self).__init__( |
| 105 | + L, |
| 106 | + name="Stanford arm", |
| 107 | + manufacturer="Victor Scheinman") |
| 108 | + |
| 109 | + @property |
| 110 | + def qz(self): |
| 111 | + return self._qz |
| 112 | + |
0 commit comments