forked from UM-ARM-Lab/pytorch_kinematics
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathtest_kinematics.py
319 lines (265 loc) · 12.9 KB
/
test_kinematics.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
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
import math
import os
from timeit import timeit
import torch
import pytorch_kinematics as pk
from pytorch_kinematics.transforms.math import quaternion_close
TEST_DIR = os.path.dirname(__file__)
def quat_pos_from_transform3d(tg):
m = tg.get_matrix()
pos = m[:, :3, 3]
rot = pk.matrix_to_quaternion(m[:, :3, :3])
return pos, rot
# test more complex robot and the MJCF parser
def test_fk_mjcf():
chain = pk.build_chain_from_mjcf(open(os.path.join(TEST_DIR, "ant.xml")).read())
chain = chain.to(dtype=torch.float64)
print(chain)
print(chain.get_joint_parameter_names())
th = {joint: 0.0 for joint in chain.get_joint_parameter_names()}
th.update({'hip_1': 1.0, 'ankle_1': 1})
ret = chain.forward_kinematics(th)
tg = ret['aux_1']
pos, rot = quat_pos_from_transform3d(tg)
assert quaternion_close(rot, torch.tensor([0.87758256, 0., 0., 0.47942554], dtype=torch.float64))
assert torch.allclose(pos, torch.tensor([0.2, 0.2, 0.75], dtype=torch.float64))
tg = ret['front_left_foot']
pos, rot = quat_pos_from_transform3d(tg)
assert quaternion_close(rot, torch.tensor([0.77015115, -0.4600326, 0.13497724, 0.42073549], dtype=torch.float64))
assert torch.allclose(pos, torch.tensor([0.13976626, 0.47635466, 0.75], dtype=torch.float64))
print(ret)
def test_fk_serial_mjcf():
chain = pk.build_serial_chain_from_mjcf(open(os.path.join(TEST_DIR, "ant.xml")).read(), 'front_left_foot')
chain = chain.to(dtype=torch.float64)
tg = chain.forward_kinematics([1.0, 1.0])
pos, rot = quat_pos_from_transform3d(tg)
assert quaternion_close(rot, torch.tensor([0.77015115, -0.4600326, 0.13497724, 0.42073549], dtype=torch.float64))
assert torch.allclose(pos, torch.tensor([0.13976626, 0.47635466, 0.75], dtype=torch.float64))
def test_fkik():
data = '<robot name="test_robot">' \
'<link name="link1" />' \
'<link name="link2" />' \
'<link name="link3" />' \
'<joint name="joint1" type="revolute">' \
'<origin xyz="1.0 0.0 0.0"/>' \
'<parent link="link1"/>' \
'<child link="link2"/>' \
'</joint>' \
'<joint name="joint2" type="revolute">' \
'<origin xyz="1.0 0.0 0.0"/>' \
'<parent link="link2"/>' \
'<child link="link3"/>' \
'</joint>' \
'</robot>'
chain = pk.build_serial_chain_from_urdf(data, 'link3')
th1 = torch.tensor([0.42553542, 0.17529176])
tg = chain.forward_kinematics(th1)
pos, rot = quat_pos_from_transform3d(tg)
assert torch.allclose(pos, torch.tensor([[1.91081784, 0.41280851, 0.0000]]))
assert quaternion_close(rot, torch.tensor([[0.95521418, 0.0000, 0.0000, 0.2959153]]))
N = 20
th_batch = torch.rand(N, 2)
tg_batch = chain.forward_kinematics(th_batch)
m = tg_batch.get_matrix()
for i in range(N):
tg = chain.forward_kinematics(th_batch[i])
assert torch.allclose(tg.get_matrix().view(4, 4), m[i])
# check that gradients are passed through
th2 = torch.tensor([0.42553542, 0.17529176], requires_grad=True)
tg = chain.forward_kinematics(th2)
pos, rot = quat_pos_from_transform3d(tg)
# note that since we are using existing operations we are not checking grad calculation correctness
assert th2.grad is None
pos.norm().backward()
assert th2.grad is not None
def test_urdf():
chain = pk.build_chain_from_urdf(open(os.path.join(TEST_DIR, "kuka_iiwa.urdf")).read())
chain.to(dtype=torch.float64)
th = [0.0, -math.pi / 4.0, 0.0, math.pi / 2.0, 0.0, math.pi / 4.0, 0.0]
ret = chain.forward_kinematics(th)
tg = ret['lbr_iiwa_link_7']
pos, rot = quat_pos_from_transform3d(tg)
assert quaternion_close(rot, torch.tensor([7.07106781e-01, 0, -7.07106781e-01, 0], dtype=torch.float64))
assert torch.allclose(pos, torch.tensor([-6.60827561e-01, 0, 3.74142136e-01], dtype=torch.float64), atol=1e-6)
def test_urdf_serial():
chain = pk.build_serial_chain_from_urdf(open(os.path.join(TEST_DIR, "kuka_iiwa.urdf")).read(), "lbr_iiwa_link_7")
chain.to(dtype=torch.float64)
th = [0.0, -math.pi / 4.0, 0.0, math.pi / 2.0, 0.0, math.pi / 4.0, 0.0]
ret = chain.forward_kinematics(th, end_only=False)
tg = ret['lbr_iiwa_link_7']
pos, rot = quat_pos_from_transform3d(tg)
assert quaternion_close(rot, torch.tensor([7.07106781e-01, 0, -7.07106781e-01, 0], dtype=torch.float64))
assert torch.allclose(pos, torch.tensor([-6.60827561e-01, 0, 3.74142136e-01], dtype=torch.float64), atol=1e-6)
N = 1000
d = "cuda" if torch.cuda.is_available() else "cpu"
dtype = torch.float64
th_batch = torch.rand(N, len(chain.get_joint_parameter_names()), dtype=dtype, device=d)
chain = chain.to(dtype=dtype, device=d)
# NOTE: Warmstart since pytorch can be slow the first time you run it
# this has to be done after you move it to the GPU. Otherwise the timing isn't representative.
for _ in range(5):
ret = chain.forward_kinematics(th)
number = 10
def _fk_parallel():
tg_batch = chain.forward_kinematics(th_batch)
m = tg_batch.get_matrix()
dt_parallel = timeit(_fk_parallel, number=number) / number
print("elapsed {}s for N={} when parallel".format(dt_parallel, N))
def _fk_serial():
for i in range(N):
tg = chain.forward_kinematics(th_batch[i])
m = tg.get_matrix()
dt_serial = timeit(_fk_serial, number=number) / number
print("elapsed {}s for N={} when serial".format(dt_serial, N))
# assert torch.allclose(tg.get_matrix().view(4, 4), m[i])
# test robot with prismatic and fixed joints
def test_fk_simple_arm():
chain = pk.build_chain_from_sdf(open(os.path.join(TEST_DIR, "simple_arm.sdf")).read())
chain = chain.to(dtype=torch.float64)
# print(chain)
# print(chain.get_joint_parameter_names())
ret = chain.forward_kinematics({
'arm_shoulder_pan_joint': 0.,
'arm_elbow_pan_joint': math.pi / 2.0,
'arm_wrist_lift_joint': -0.5,
'arm_wrist_roll_joint': 0.,
})
tg = ret['arm_wrist_roll']
pos, rot = quat_pos_from_transform3d(tg)
assert quaternion_close(rot, torch.tensor([0.70710678, 0., 0., 0.70710678], dtype=torch.float64))
assert torch.allclose(pos, torch.tensor([1.05, 0.55, 0.5], dtype=torch.float64))
N = 100
ret = chain.forward_kinematics({k: torch.rand(N) for k in chain.get_joint_parameter_names()})
tg = ret['arm_wrist_roll']
assert list(tg.get_matrix().shape) == [N, 4, 4]
def test_sdf_serial_chain():
chain = pk.build_serial_chain_from_sdf(open(os.path.join(TEST_DIR, "simple_arm.sdf")).read(), 'arm_wrist_roll')
chain = chain.to(dtype=torch.float64)
tg = chain.forward_kinematics([0., math.pi / 2.0, -0.5, 0.])
pos, rot = quat_pos_from_transform3d(tg)
assert quaternion_close(rot, torch.tensor([0.70710678, 0., 0., 0.70710678], dtype=torch.float64))
assert torch.allclose(pos, torch.tensor([1.05, 0.55, 0.5], dtype=torch.float64))
def test_cuda():
if torch.cuda.is_available():
d = "cuda"
dtype = torch.float64
chain = pk.build_chain_from_sdf(open(os.path.join(TEST_DIR, "simple_arm.sdf")).read())
# noinspection PyUnusedLocal
chain = chain.to(dtype=dtype, device=d)
# NOTE: do it twice because we previously had an issue with default arguments
# like joint=Joint() causing spooky behavior
chain = pk.build_chain_from_sdf(open(os.path.join(TEST_DIR, "simple_arm.sdf")).read())
chain = chain.to(dtype=dtype, device=d)
ret = chain.forward_kinematics({
'arm_shoulder_pan_joint': 0,
'arm_elbow_pan_joint': math.pi / 2.0,
'arm_wrist_lift_joint': -0.5,
'arm_wrist_roll_joint': 0,
})
tg = ret['arm_wrist_roll']
pos, rot = quat_pos_from_transform3d(tg)
assert quaternion_close(rot, torch.tensor([0.70710678, 0., 0., 0.70710678], dtype=dtype, device=d))
assert torch.allclose(pos, torch.tensor([1.05, 0.55, 0.5], dtype=dtype, device=d))
data = '<robot name="test_robot">' \
'<link name="link1" />' \
'<link name="link2" />' \
'<link name="link3" />' \
'<joint name="joint1" type="revolute">' \
'<origin xyz="1.0 0.0 0.0"/>' \
'<parent link="link1"/>' \
'<child link="link2"/>' \
'</joint>' \
'<joint name="joint2" type="revolute">' \
'<origin xyz="1.0 0.0 0.0"/>' \
'<parent link="link2"/>' \
'<child link="link3"/>' \
'</joint>' \
'</robot>'
chain = pk.build_serial_chain_from_urdf(data, 'link3')
chain = chain.to(dtype=dtype, device=d)
N = 20
th_batch = torch.rand(N, 2).to(device=d, dtype=dtype)
tg_batch = chain.forward_kinematics(th_batch)
m = tg_batch.get_matrix()
for i in range(N):
tg = chain.forward_kinematics(th_batch[i])
assert torch.allclose(tg.get_matrix().view(4, 4), m[i])
# FIXME: comment out because compound joints are no longer implemented
# def test_fk_mjcf_humanoid():
# chain = pk.build_chain_from_mjcf(open(os.path.join(TEST_DIR, "humanoid.xml")).read())
# print(chain)
# print(chain.get_joint_parameter_names())
# th = {'left_knee': 0.0, 'right_knee': 0.0}
# ret = chain.forward_kinematics(th)
# print(ret)
def test_mjcf_slide_joint_parsing():
# just testing that we can parse it without error
# the slide joint is not actually of a link to another link, but instead of the base to the world
# which we do not represent
chain = pk.build_chain_from_mjcf(open(os.path.join(TEST_DIR, "hopper.xml")).read())
print(chain.get_joint_parameter_names())
print(chain.get_frame_names())
def test_fk_val():
chain = pk.build_chain_from_mjcf(open(os.path.join(TEST_DIR, "val.xml")).read())
chain = chain.to(dtype=torch.float64)
ret = chain.forward_kinematics(torch.zeros([1000, chain.n_joints], dtype=torch.float64))
tg = ret['drive45']
pos, rot = quat_pos_from_transform3d(tg)
torch.set_printoptions(precision=6, sci_mode=False)
assert quaternion_close(rot, torch.tensor([0.5, 0.5, -0.5, 0.5], dtype=torch.float64))
assert torch.allclose(pos, torch.tensor([-0.225692, 0.259045, 0.262139], dtype=torch.float64))
def test_fk_partial_batched_dict():
# Test that you can pass in dict of batched joint configs for a subset of the joints
chain = pk.build_serial_chain_from_mjcf(open(os.path.join(TEST_DIR, "val.xml")).read(), 'left_tool')
th = {
'joint56': torch.zeros([1000], dtype=torch.float64),
'joint57': torch.zeros([1000], dtype=torch.float64),
'joint41': torch.zeros([1000], dtype=torch.float64),
'joint42': torch.zeros([1000], dtype=torch.float64),
'joint43': torch.zeros([1000], dtype=torch.float64),
'joint44': torch.zeros([1000], dtype=torch.float64),
'joint45': torch.zeros([1000], dtype=torch.float64),
'joint46': torch.zeros([1000], dtype=torch.float64),
'joint47': torch.zeros([1000], dtype=torch.float64),
}
chain = chain.to(dtype=torch.float64)
tg = chain.forward_kinematics(th)
def test_fk_partial_batched():
# Test that you can pass in dict of batched joint configs for a subset of the joints
chain = pk.build_serial_chain_from_mjcf(open(os.path.join(TEST_DIR, "val.xml")).read(), 'left_tool')
th = torch.zeros([1000, 9], dtype=torch.float64)
chain = chain.to(dtype=torch.float64)
tg = chain.forward_kinematics(th)
def test_ur5_fk():
urdf = os.path.join(TEST_DIR, "ur5.urdf")
pk_chain = pk.build_serial_chain_from_urdf(open(urdf).read(), 'ee_link', 'base_link')
th = [0.0, -math.pi / 4.0, 0.0, math.pi / 2.0, 0.0, math.pi / 4.0]
try:
import ikpy.chain
ik_chain = ikpy.chain.Chain.from_urdf_file(urdf,
active_links_mask=[False, True, True, True, True, True, True, False])
ik_ret = ik_chain.forward_kinematics([0, *th, 0])
except ImportError:
ik_ret = [[-6.44330720e-18, 3.58979314e-09, -1.00000000e+00, 5.10955359e-01],
[1.00000000e+00, 1.79489651e-09, 0.00000000e+00, 1.91450000e-01],
[1.79489651e-09, -1.00000000e+00, -3.58979312e-09, 6.00114361e-01],
[0.00000000e+00, 0.00000000e+00, 0.00000000e+00, 1.00000000e+00]]
ret = pk_chain.forward_kinematics(th, end_only=True)
print(ret.get_matrix())
ik_ret = torch.tensor(ik_ret, dtype=ret.dtype)
print(ik_ret)
assert torch.allclose(ik_ret, ret.get_matrix(), atol=1e-6)
if __name__ == "__main__":
test_fk_partial_batched()
test_fk_partial_batched_dict()
test_fk_val()
test_sdf_serial_chain()
test_urdf_serial()
test_fkik()
test_fk_simple_arm()
test_fk_mjcf()
test_cuda()
test_urdf()
# test_fk_mjcf_humanoid()
test_mjcf_slide_joint_parsing()
test_ur5_fk()