-
Notifications
You must be signed in to change notification settings - Fork 499
/
Copy pathtest_models.py
177 lines (140 loc) · 3.48 KB
/
test_models.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
#!/usr/bin/env python3
"""
@author: Jesse Haviland
"""
import roboticstoolbox as rp
import unittest
import numpy.testing as nt
class TestModels(unittest.TestCase):
def test_list(self):
rp.models.list()
rp.models.list('UR', 6)
rp.models.list(mtype='DH')
def test_puma(self):
puma = rp.models.DH.Puma560()
puma.qr
puma.qz
puma.qs
puma.qn
puma = rp.models.DH.Puma560(symbolic=True)
def test_pumaURDF(self):
puma = rp.models.Puma560()
puma.qr
puma.qz
puma.qs
puma.qn
def test_frankie(self):
frankie = rp.models.ETS.Frankie()
frankie.qr
frankie.qz
def test_PandaURDF(self):
panda = rp.models.Panda()
panda.qr
panda.qz
def test_UR3(self):
ur = rp.models.UR3()
ur.qr
ur.qz
def test_UR5(self):
ur = rp.models.UR5()
ur.qr
ur.qz
def test_UR10(self):
ur = rp.models.UR10()
ur.qr
ur.qz
def test_px100(self):
r = rp.models.px100()
r.qr
r.qz
def test_px150(self):
r = rp.models.px150()
r.qr
r.qz
def test_rx150(self):
r = rp.models.rx150()
r.qr
r.qz
def test_rx200(self):
r = rp.models.rx200()
r.qr
r.qz
def test_vx300(self):
r = rp.models.vx300()
r.qr
r.qz
def test_vx300s(self):
r = rp.models.vx300s()
r.qr
r.qz
def test_wx200(self):
r = rp.models.wx200()
r.qr
r.qz
def test_wx250(self):
r = rp.models.wx250()
r.qr
r.qz
def test_wx250s(self):
r = rp.models.wx250s()
r.qr
r.qz
def test_Mico(self):
r = rp.models.Mico()
r.qr
r.qz
def test_ball(self):
r = rp.models.DH.Ball()
r.qz
r.q1
def test_stanford(self):
r = rp.models.DH.Stanford()
r.qz
def test_planar3(self):
r = rp.models.DH.Planar3()
r.qz
def test_planar2(self):
r = rp.models.DH.Planar2()
r.qz
def test_orion5(self):
r = rp.models.DH.Orion5()
r.qz
r.qv
r.qh
def test_lwr4(self):
r = rp.models.DH.LWR4()
r.qz
def test_kr5(self):
r = rp.models.DH.KR5()
r.qz
def test_irb140(self):
r = rp.models.DH.IRB140()
r.qz
def test_cobra600(self):
r = rp.models.DH.Cobra600()
r.qz
def test_pr2(self):
rp.models.PR2()
def test_ikine_a_puma(self):
# self.skipTest("Need new spatialmath pypi release")
r0 = rp.models.DH.Puma560()
q = r0.qr
T = r0.fkine(q)
qr0 = [
2.68943591e-01, 1.61780018e+00, -1.57079633e+00, -1.43934287e-18,
-4.70038498e-02, -2.68943591e-01]
qr1 = [
1.77635684e-15, 1.57079633e+00, -1.57079633e+00, 3.14159265e+00,
-5.77315973e-15, 3.14159265e+00]
sol0 = r0.ikine_a(T)
sol1 = r0.ikine_a(T, 'rdf')
nt.assert_array_almost_equal(sol0.q, qr0, decimal=4)
nt.assert_array_almost_equal(sol1.q, qr1, decimal=4)
def test_fkine_urdf(self):
for model_name in rp.models.URDF.__all__:
m = getattr(rp.models.URDF, model_name)
r = m()
r.fkine(r.q)
if __name__ == '__main__': # pragma nocover
unittest.main()
# pytest.main(['tests/test_SerialLink.py'])