-
Notifications
You must be signed in to change notification settings - Fork 499
/
Copy pathtest_ERobot.py
245 lines (192 loc) · 8.16 KB
/
test_ERobot.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
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
#!/usr/bin/env python3
"""
Created on Fri May 1 14:04:04 2020
@author: Jesse Haviland
"""
import numpy.testing as nt
import numpy as np
import roboticstoolbox as rtb
from roboticstoolbox import ERobot, ET, ETS, Link
# from spatialmath import SE2, SE3
import unittest
import spatialmath as sm
import spatialgeometry as gm
from math import pi, sin, cos
try:
from sympy import symbols, simplify
from sympy import sin as ssin
from sympy import cos as scos
_sympy = True
except ModuleNotFoundError:
_sympy = False
class TestERobot(unittest.TestCase):
def test_jacobm(self):
panda = rtb.models.ETS.Panda()
q1 = np.array([1.4, 0.2, 1.8, 0.7, 0.1, 3.1, 2.9])
q2 = [1.4, 0.2, 1.8, 0.7, 0.1, 3.1, 2.9]
q3 = np.expand_dims(q1, 0)
q4 = np.expand_dims(q1, 1)
ans = np.array(
[
[1.27080875e-17],
[2.38242538e-02],
[6.61029519e-03],
[8.18202121e-03],
[7.74546204e-04],
[-1.10885380e-02],
[0.00000000e00],
]
)
panda.q = q1
nt.assert_array_almost_equal(panda.jacobm(), ans)
nt.assert_array_almost_equal(panda.jacobm(q2), ans)
nt.assert_array_almost_equal(panda.jacobm(q3), ans)
nt.assert_array_almost_equal(panda.jacobm(q4), ans)
nt.assert_array_almost_equal(panda.jacobm(J=panda.jacob0(q1)), ans)
# self.assertRaises(ValueError, panda.jacobm)
self.assertRaises(TypeError, panda.jacobm, "Wfgsrth")
self.assertRaises(ValueError, panda.jacobm, [1, 3], np.array([1, 5]))
self.assertRaises(TypeError, panda.jacobm, [1, 3], "qwe")
self.assertRaises(TypeError, panda.jacobm, [1, 3], panda.jacob0(q1), [1, 2, 3])
self.assertRaises(
ValueError, panda.jacobm, [1, 3], panda.jacob0(q1), np.array([1, 2, 3])
)
def test_dict(self):
panda = rtb.models.Panda()
panda.grippers[0].links[0].collision.append(gm.Cuboid([1, 1, 1]))
panda._to_dict()
wx = rtb.models.wx250s()
wx._to_dict()
def test_fkdict(self):
panda = rtb.models.Panda()
panda.grippers[0].links[0].collision.append(gm.Cuboid([1, 1, 1]))
panda._fk_dict()
def test_dist(self):
s0 = gm.Cuboid([1, 1, 1], pose=sm.SE3(0, 0, 0))
s1 = gm.Cuboid([1, 1, 1], pose=sm.SE3(3, 0, 0))
p = rtb.models.Panda()
d0, _, _ = p.closest_point(p.q, s0)
d1, _, _ = p.closest_point(p.q, s1, 5)
d2, _, _ = p.closest_point(p.q, s1)
self.assertAlmostEqual(d0, -0.5599999999995913) # type: ignore
self.assertAlmostEqual(d1, 2.362147178773918) # type: ignore
self.assertAlmostEqual(d2, None) # type: ignore
def test_collided(self):
s0 = gm.Cuboid([1, 1, 1], pose=sm.SE3(0, 0, 0))
s1 = gm.Cuboid([1, 1, 1], pose=sm.SE3(3, 0, 0))
p = rtb.models.Panda()
c0 = p.collided(p.q, s0)
c1 = p.collided(p.q, s1)
self.assertTrue(c0)
self.assertFalse(c1)
def test_invdyn(self):
# create a 2 link robot
# Example from Spong etal. 2nd edition, p. 260
l1 = Link(ets=ETS(ET.Ry()), m=1, r=[0.5, 0, 0], name="l1")
l2 = Link(ets=ETS(ET.tx(1)) * ET.Ry(), m=1, r=[0.5, 0, 0], parent=l1, name="l2")
robot = ERobot([l1, l2], name="simple 2 link")
z = np.zeros(robot.n)
# check gravity load
tau = robot.rne(z, z, z) / 9.81
nt.assert_array_almost_equal(tau, np.r_[-2, -0.5])
tau = robot.rne(np.array([0.0, -pi / 2.0]), z, z) / 9.81
nt.assert_array_almost_equal(tau, np.r_[-1.5, 0])
tau = robot.rne(np.array([-pi / 2, pi / 2]), z, z) / 9.81
nt.assert_array_almost_equal(tau, np.r_[-0.5, -0.5])
tau = robot.rne(np.array([-pi / 2, 0]), z, z) / 9.81
nt.assert_array_almost_equal(tau, np.r_[0, 0])
# check velocity terms
robot.gravity = [0, 0, 0]
q = np.array([0, -pi / 2])
h = -0.5 * sin(q[1])
tau = robot.rne(q, np.array([0, 0]), z)
nt.assert_array_almost_equal(tau, np.r_[0, 0] * h)
tau = robot.rne(q, np.array([1, 0]), z)
nt.assert_array_almost_equal(tau, np.r_[0, -1] * h)
tau = robot.rne(q, np.array([0, 1]), z)
nt.assert_array_almost_equal(tau, np.r_[1, 0] * h)
tau = robot.rne(q, np.array([1, 1]), z)
nt.assert_array_almost_equal(tau, np.r_[3, -1] * h)
# check inertial terms
d11 = 1.5 + cos(q[1])
d12 = 0.25 + 0.5 * cos(q[1])
d21 = d12
d22 = 0.25
tau = robot.rne(q, z, np.array([0, 0]))
nt.assert_array_almost_equal(tau, np.r_[0, 0])
tau = robot.rne(q, z, np.array([1, 0]))
nt.assert_array_almost_equal(tau, np.r_[d11, d21])
tau = robot.rne(q, z, np.array([0, 1]))
nt.assert_array_almost_equal(tau, np.r_[d12, d22])
tau = robot.rne(q, z, np.array([1, 1]))
nt.assert_array_almost_equal(tau, np.r_[d11 + d12, d21 + d22])
def test_URDF_inertia(self):
robot = rtb.models.URDF.UR10()
try:
robot.inertia(robot.q)
except TypeError:
self.fail("inertia() with a robot containing fixed links raised an error")
class TestERobot2(unittest.TestCase):
def test_plot(self):
robot = rtb.models.ETS.Planar2()
e = robot.plot(robot.qz, block=False, name=True)
e.close()
def test_teach(self):
robot = rtb.models.ETS.Planar2()
e = robot.teach(robot.qz, block=False)
e.close()
e = robot.teach(robot.qz, block=False)
e.close()
def test_plot_with_vellipse(self):
robot = rtb.models.ETS.Planar2()
e = robot.plot(
robot.qb, block=False, name=True, vellipse=True, limits=[1, 2, 1, 2]
)
e.step()
e.close()
def test_plot_with_fellipse(self):
robot = rtb.models.ETS.Planar2()
e = robot.plot(
robot.qz, block=False, name=True, dellipse=True, limits=[1, 2, 1, 2]
)
e.step()
e.close()
def test_base(self):
robot = rtb.models.ETS.Planar2()
nt.assert_almost_equal(robot.base.A, sm.SE2().A)
def test_jacobe(self):
robot = rtb.models.ETS.Planar2()
J = robot.jacobe(robot.qz)
a1 = np.array([[0.0, 0.0], [2.0, 1.0], [1.0, 1.0]])
nt.assert_almost_equal(J, a1)
@unittest.skipUnless(_sympy, "sympy not installed")
def test_symdyn(self):
a1, a2, r1, r2, m1, m2, g = symbols("a1 a2 r1 r2 m1 m2 g")
link1 = Link(ET.Ry(flip=True), m=m1, r=[r1, 0, 0], name="link0")
link2 = Link(ET.tx(a1) * ET.Ry(flip=True), m=m2, r=[r2, 0, 0], name="link1")
robot = ERobot([link1, link2])
# Define symbols
q = symbols("q:2")
qd = symbols("qd:2")
qdd = symbols("qdd:2")
q0, q1 = q
qd0, qd1 = qd
qdd0, qdd1 = qdd
Q = robot.rne(q, qd, qdd, gravity=[0, 0, g], symbolic=True)
solution_0 = a1**2*m2*qd0**2*ssin(q1)*scos(q1) + a1*qd0*(-a1*m2*qd0*scos(q1) - \
m2*r2*(qd0 + qd1))*ssin(q1) - a1*(m2*(a1*qd0*qd1*scos(q1) - \
a1*qdd0*ssin(q1) - g*ssin(q0)*scos(q1) - g*ssin(q1)*scos(q0)) + \
(qd0 + qd1)*(-a1*m2*qd0*scos(q1) - m2*r2*(qd0 + qd1)))*ssin(q1) - \
a1*(-a1*m2*qd0*(-qd0 - qd1)*ssin(q1) - m2*r2*(qdd0 + qdd1) + \
m2*(-a1*qd0*qd1*ssin(q1) - a1*qdd0*scos(q1) + g*ssin(q0)*ssin(q1) - \
g*scos(q0)*scos(q1)))*scos(q1) + g*m1*r1*scos(q0) + m1*qdd0*r1**2 + \
m2*r2**2*(qdd0 + qdd1) - m2*r2*(-a1*qd0*qd1*ssin(q1) - \
a1*qdd0*scos(q1) + g*ssin(q0)*ssin(q1) - g*scos(q0)*scos(q1))
solution_1 = a1**2*m2*qd0**2*ssin(q1)*scos(q1) + a1*qd0*(-a1*m2*qd0*scos(q1) - \
m2*r2*(qd0 + qd1))*ssin(q1) + m2*r2**2*(qdd0 + qdd1) - \
m2*r2*(-a1*qd0*qd1*ssin(q1) - a1*qdd0*scos(q1) + g*ssin(q0)*ssin(q1) - \
g*scos(q0)*scos(q1))
self.assertEqual(simplify(Q[0]-solution_0), 0)
self.assertEqual(simplify(Q[1]-solution_1), 0)
if __name__ == "__main__": # pragma nocover
unittest.main()