IK with CollisionΒΆ
Basic Inverse Kinematics with Collision Avoidance using PyRoKi.
All examples can be run by first cloning the PyRoki repository, which includes the pyroki_snippets
implementation details.
1import time
2
3import numpy as np
4import pyroki as pk
5import viser
6from pyroki.collision import HalfSpace, RobotCollision, Sphere
7from robot_descriptions.loaders.yourdfpy import load_robot_description
8from viser.extras import ViserUrdf
9
10import pyroki_snippets as pks
11
12
13def main():
14 """Main function for basic IK with collision."""
15 urdf = load_robot_description("panda_description")
16 target_link_name = "panda_hand"
17 robot = pk.Robot.from_urdf(urdf)
18
19 robot_coll = RobotCollision.from_urdf(urdf)
20 plane_coll = HalfSpace.from_point_and_normal(
21 np.array([0.0, 0.0, 0.0]), np.array([0.0, 0.0, 1.0])
22 )
23 sphere_coll = Sphere.from_center_and_radius(
24 np.array([0.0, 0.0, 0.0]), np.array([0.05])
25 )
26
27 # Set up visualizer.
28 server = viser.ViserServer()
29 server.scene.add_grid("/ground", width=2, height=2, cell_size=0.1)
30 urdf_vis = ViserUrdf(server, urdf, root_node_name="/robot")
31
32 # Create interactive controller for IK target.
33 ik_target_handle = server.scene.add_transform_controls(
34 "/ik_target", scale=0.2, position=(0.5, 0.0, 0.5), wxyz=(0, 0, 1, 0)
35 )
36
37 # Create interactive controller and mesh for the sphere obstacle.
38 sphere_handle = server.scene.add_transform_controls(
39 "/obstacle", scale=0.2, position=(0.4, 0.3, 0.4)
40 )
41 server.scene.add_mesh_trimesh("/obstacle/mesh", mesh=sphere_coll.to_trimesh())
42
43 timing_handle = server.gui.add_number("Elapsed (ms)", 0.001, disabled=True)
44
45 while True:
46 start_time = time.time()
47
48 sphere_coll_world_current = sphere_coll.transform_from_wxyz_position(
49 wxyz=np.array(sphere_handle.wxyz),
50 position=np.array(sphere_handle.position),
51 )
52
53 world_coll_list = [plane_coll, sphere_coll_world_current]
54 solution = pks.solve_ik_with_collision(
55 robot=robot,
56 coll=robot_coll,
57 world_coll_list=world_coll_list,
58 target_link_name=target_link_name,
59 target_position=np.array(ik_target_handle.position),
60 target_wxyz=np.array(ik_target_handle.wxyz),
61 )
62
63 # Update timing handle.
64 timing_handle.value = (time.time() - start_time) * 1000
65
66 # Update visualizer.
67 urdf_vis.update_cfg(solution)
68
69
70if __name__ == "__main__":
71 main()