6
6
from roboticstoolbox import DHRobot , RevoluteMDH
7
7
from spatialmath import SE3
8
8
9
+
9
10
class AL5D (DHRobot ):
10
11
"""
11
12
Class that models a Lynxmotion AL5D manipulator
@@ -41,48 +42,50 @@ def __init__(self, symbolic=False):
41
42
42
43
if symbolic :
43
44
import spatialmath .base .symbolic as sym
45
+
44
46
zero = sym .zero ()
45
47
pi = sym .pi ()
46
48
else :
47
49
from math import pi
50
+
48
51
zero = 0.0
49
52
50
53
# robot length values (metres)
51
54
a = [0 , 0.002 , 0.14679 , 0.17751 ]
52
55
d = [- 0.06858 , 0 , 0 , 0 ]
53
56
54
- alpha = [pi , pi / 2 , pi , pi ]
55
- offset = [pi / 2 , pi , - 0.0427 , - 0.0427 - pi / 2 ]
57
+ alpha = [pi , pi / 2 , pi , pi ]
58
+ offset = [pi / 2 , pi , - 0.0427 , - 0.0427 - pi / 2 ]
56
59
57
60
# mass data as measured
58
61
mass = [0.187 , 0.044 , 0.207 , 0.081 ]
59
62
60
63
# center of mass as calculated through CAD model
61
64
center_of_mass = [
62
- [0.01724 , - 0.00389 , 0.00468 ],
63
- [0.07084 , 0.00000 , 0.00190 ],
64
- [0.05615 , - 0.00251 , - 0.00080 ],
65
- [0.04318 , 0.00735 , - 0.00523 ],
66
- ]
65
+ [0.01724 , - 0.00389 , 0.00468 ],
66
+ [0.07084 , 0.00000 , 0.00190 ],
67
+ [0.05615 , - 0.00251 , - 0.00080 ],
68
+ [0.04318 , 0.00735 , - 0.00523 ],
69
+ ]
67
70
68
71
# moments of inertia are practically zero
69
72
moments_of_inertia = [
70
- [0 , 0 , 0 , 0 , 0 , 0 ],
71
- [0 , 0 , 0 , 0 , 0 , 0 ],
72
- [0 , 0 , 0 , 0 , 0 , 0 ],
73
- [0 , 0 , 0 , 0 , 0 , 0 ]
74
- ]
73
+ [0 , 0 , 0 , 0 , 0 , 0 ],
74
+ [0 , 0 , 0 , 0 , 0 , 0 ],
75
+ [0 , 0 , 0 , 0 , 0 , 0 ],
76
+ [0 , 0 , 0 , 0 , 0 , 0 ],
77
+ ]
75
78
76
79
joint_limits = [
77
- [- pi / 2 , pi / 2 ],
78
- [- pi / 2 , pi / 2 ],
79
- [- pi , 2 , pi / 2 ],
80
- [- pi / 2 , pi / 2 ],
81
- ]
80
+ [- pi / 2 , pi / 2 ],
81
+ [- pi / 2 , pi / 2 ],
82
+ [- pi / 2 , pi / 2 ],
83
+ [- pi / 2 , pi / 2 ],
84
+ ]
82
85
83
86
links = []
84
87
85
- for j in range (4 ):
88
+ for j in range (3 ):
86
89
link = RevoluteMDH (
87
90
d = d [j ],
88
91
a = a [j ],
@@ -92,27 +95,28 @@ def __init__(self, symbolic=False):
92
95
I = moments_of_inertia [j ],
93
96
G = 1 ,
94
97
B = 0 ,
95
- Tc = [0 ,0 ],
96
- qlim = joint_limits [j ]
98
+ Tc = [0 , 0 ],
99
+ qlim = joint_limits [j ],
97
100
)
98
101
links .append (link )
99
-
100
- tool = SE3 (0.07719 ,0 , 0 )
101
-
102
+
103
+ tool = SE3 (0.07719 , 0 , 0 )
104
+
102
105
super ().__init__ (
103
106
links ,
104
107
name = "AL5D" ,
105
108
manufacturer = "Lynxmotion" ,
106
- keywords = (' dynamics' , ' symbolic' ),
109
+ keywords = (" dynamics" , " symbolic" ),
107
110
symbolic = symbolic ,
108
- tool = tool
111
+ tool = tool ,
109
112
)
110
-
113
+
111
114
# zero angles
112
- self .addconfiguration ("home" , np .array ([pi / 2 , pi / 2 , pi / 2 , pi / 2 ]))
115
+ self .addconfiguration ("home" , np .array ([pi / 2 , pi / 2 , pi / 2 , pi / 2 ]))
116
+
113
117
114
- if __name__ == ' __main__' : # pragma nocover
118
+ if __name__ == " __main__" : # pragma nocover
115
119
116
120
al5d = AL5D (symbolic = False )
117
121
print (al5d )
118
- print (al5d .dyntable ())
122
+ # print(al5d.dyntable())
0 commit comments