Skip to content

Commit 595247e

Browse files
author
Peter
committed
remove C++ for portability/compatibility
1 parent 1246088 commit 595247e

File tree

6 files changed

+3
-187
lines changed

6 files changed

+3
-187
lines changed

pyproject.toml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -71,5 +71,5 @@ mujoco = ["mujoco"]
7171
[build-system]
7272
# Including torch and ninja here are needed to build the native code.
7373
# They will be installed as dependencies during the build, which can take a while the first time.
74-
requires = ["setuptools>=60.0.0", "wheel", "torch==2.1.0", "ninja"]
74+
requires = ["setuptools>=60.0.0", "wheel"]
7575
build-backend= "setuptools.build_meta"

setup.py

Lines changed: 0 additions & 14 deletions
This file was deleted.

src/pytorch_kinematics/chain.py

Lines changed: 0 additions & 37 deletions
Original file line numberDiff line numberDiff line change
@@ -281,44 +281,7 @@ def get_link_names(self):
281281
def get_frame_indices(self, *frame_names):
282282
return torch.tensor([self.frame_to_idx[n] for n in frame_names], dtype=torch.long,
283283
device=self.device)
284-
285284
def forward_kinematics(self, th, frame_indices: Optional = None):
286-
"""
287-
Compute forward kinematics.
288-
289-
Args:
290-
th: A dict, list, numpy array, or torch tensor of ALL joints values. Possibly batched.
291-
the fastest thing to use is a torch tensor, all other types get converted to that.
292-
If any joint values are missing, an exception will be thrown.
293-
frame_indices: A list of frame indices to compute forward kinematics for. If None, all frames are computed.
294-
295-
Returns:
296-
A dict of frame names and their corresponding Transform3d objects.
297-
"""
298-
if frame_indices is None:
299-
frame_indices = self.get_all_frame_indices()
300-
301-
th = self.ensure_tensor(th)
302-
th = torch.atleast_2d(th)
303-
304-
import zpk_cpp
305-
frame_transforms = zpk_cpp.fk(
306-
frame_indices,
307-
self.axes,
308-
th,
309-
self.parents_indices,
310-
self.joint_type_indices,
311-
self.joint_indices,
312-
self.joint_offsets,
313-
self.link_offsets
314-
)
315-
316-
frame_names_and_transform3ds = {self.idx_to_frame[frame_idx]: tf.Transform3d(matrix=transform) for
317-
frame_idx, transform in frame_transforms.items()}
318-
319-
return frame_names_and_transform3ds
320-
321-
def forward_kinematics_py(self, th, frame_indices: Optional = None):
322285
if frame_indices is None:
323286
frame_indices = self.get_all_frame_indices()
324287

src/zpk_cpp/pk.cpp

Lines changed: 0 additions & 107 deletions
This file was deleted.

tests/test_kinematics.py

Lines changed: 2 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -255,34 +255,9 @@ def test_mjcf_slide_joint_parsing():
255255

256256

257257
def test_fk_val():
258-
dtype = torch.float64
259-
d = "cuda" if torch.cuda.is_available() else "cpu"
260-
261258
chain = pk.build_chain_from_mjcf(open(os.path.join(TEST_DIR, "val.xml")).read())
262-
chain = chain.to(dtype=torch.float64, device=d)
263-
264-
th = torch.rand(1000, chain.n_joints, dtype=dtype, device=d)
265-
266-
def _fk_no_compile():
267-
return chain.forward_kinematics_py(th)
268-
269-
@torch.compile(backend='inductor')
270-
def _fk_compile():
271-
return chain.forward_kinematics_py(th)
272-
273-
from timeit import timeit
274-
275-
# warmup
276-
_fk_no_compile()
277-
_fk_compile()
278-
279-
number = 10
280-
ms_no_compile = timeit(_fk_no_compile, number=number) / number * 1000
281-
print(f"elapsed {ms_no_compile:.1f}ms for no compile")
282-
ms_compile = timeit(_fk_compile, number=number) / number * 1000
283-
print(f"elapsed {ms_compile:.1f}ms for compile")
284-
285-
ret = chain.forward_kinematics_py(th)
259+
chain = chain.to(dtype=torch.float64)
260+
ret = chain.forward_kinematics(torch.zeros([1000, chain.n_joints], dtype=torch.float64))
286261
tg = ret['drive45']
287262
pos, rot = quat_pos_from_transform3d(tg)
288263
torch.set_printoptions(precision=6, sci_mode=False)

tests/test_rotation_conversions.py

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,6 @@
44

55
from pytorch_kinematics.transforms.rotation_conversions import axis_and_angle_to_matrix, axis_angle_to_matrix, \
66
pos_rot_to_matrix, matrix_to_pos_rot, random_rotations
7-
import zpk_cpp
87

98

109
def test_axis_angle_to_matrix_perf():

0 commit comments

Comments
 (0)