-
Notifications
You must be signed in to change notification settings - Fork 2.8k
Expand file tree
/
Copy pathfranka_cube.py
More file actions
92 lines (78 loc) · 2.52 KB
/
franka_cube.py
File metadata and controls
92 lines (78 loc) · 2.52 KB
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
import argparse
import numpy as np
import genesis as gs
def main():
parser = argparse.ArgumentParser()
parser.add_argument("-v", "--vis", action="store_true", default=False)
args = parser.parse_args()
########################## init ##########################
gs.init(backend=gs.gpu, precision="32")
########################## create a scene ##########################
scene = gs.Scene(
viewer_options=gs.options.ViewerOptions(
camera_pos=(3, -1, 1.5),
camera_lookat=(0.0, 0.0, 0.5),
camera_fov=30,
res=(960, 640),
),
sim_options=gs.options.SimOptions(
dt=0.01,
),
rigid_options=gs.options.RigidOptions(
box_box_detection=True,
),
show_viewer=args.vis,
)
########################## entities ##########################
plane = scene.add_entity(
gs.morphs.Plane(),
)
franka = scene.add_entity(
gs.morphs.MJCF(file="xml/franka_emika_panda/panda.xml"),
)
cube = scene.add_entity(
gs.morphs.Box(
size=(0.04, 0.04, 0.04),
pos=(0.65, 0.0, 0.02),
)
)
########################## build ##########################
scene.build()
motors_dof = np.arange(7)
fingers_dof = np.arange(7, 9)
franka.set_dofs_kp([100.0, 100.0], fingers_dof)
franka.set_dofs_kv([10.0, 10.0], fingers_dof)
qpos = np.array([-1.0124, 1.5559, 1.3662, -1.6878, -1.5799, 1.7757, 1.4602, 0.04, 0.04])
franka.set_qpos(qpos)
scene.step()
end_effector = franka.get_link("hand")
qpos = franka.inverse_kinematics(
link=end_effector,
pos=np.array([0.65, 0.0, 0.135]),
quat=np.array([0, 1, 0, 0]),
)
franka.control_dofs_position(qpos[:-2], motors_dof)
# hold
for i in range(100):
print("hold", i)
scene.step()
# grasp
finder_pos = -0.0
for i in range(100):
print("grasp", i)
franka.control_dofs_position(qpos[:-2], motors_dof)
franka.control_dofs_position(np.array([finder_pos, finder_pos]), fingers_dof)
scene.step()
# lift
qpos = franka.inverse_kinematics(
link=end_effector,
pos=np.array([0.65, 0.0, 0.3]),
quat=np.array([0, 1, 0, 0]),
)
for i in range(200):
print("lift", i)
franka.control_dofs_position(qpos[:-2], motors_dof)
franka.control_dofs_position(np.array([finder_pos, finder_pos]), fingers_dof)
scene.step()
if __name__ == "__main__":
main()