forked from kevinzakka/mink
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathhumanoid_g1.py
128 lines (109 loc) · 4.28 KB
/
humanoid_g1.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
from pathlib import Path
import mujoco
import mujoco.viewer
from loop_rate_limiters import RateLimiter
import mink
_HERE = Path(__file__).parent
_XML = _HERE / "unitree_g1" / "scene_table.xml"
if __name__ == "__main__":
model = mujoco.MjModel.from_xml_path(_XML.as_posix())
configuration = mink.Configuration(model)
feet = ["right_foot", "left_foot"]
hands = ["right_palm", "left_palm"]
tasks = [
pelvis_orientation_task := mink.FrameTask(
frame_name="pelvis",
frame_type="body",
position_cost=0.0,
orientation_cost=1.0,
lm_damping=1.0,
),
torso_orientation_task := mink.FrameTask(
frame_name="torso_link",
frame_type="body",
position_cost=0.0,
orientation_cost=1.0,
lm_damping=1.0,
),
posture_task := mink.PostureTask(model, cost=1e-1),
com_task := mink.ComTask(cost=10.0),
]
feet_tasks = []
for foot in feet:
task = mink.FrameTask(
frame_name=foot,
frame_type="site",
position_cost=10.0,
orientation_cost=1.0,
lm_damping=1.0,
)
feet_tasks.append(task)
tasks.extend(feet_tasks)
hand_tasks = []
for hand in hands:
task = mink.FrameTask(
frame_name=hand,
frame_type="site",
position_cost=5.0,
orientation_cost=1.0,
lm_damping=1.0,
)
hand_tasks.append(task)
tasks.extend(hand_tasks)
# Enable collision avoidance between the following geoms.
# left hand - table, right hand - table
# left hand - left thigh, right hand - right thigh
collision_pairs = [
(["left_hand_collision", "right_hand_collision"], ["table"]),
(["left_hand_collision"], ["left_thigh"]),
(["right_hand_collision"], ["right_thigh"]),
]
collision_avoidance_limit = mink.CollisionAvoidanceLimit(
model=model,
geom_pairs=collision_pairs, # type: ignore
minimum_distance_from_collisions=0.05,
collision_detection_distance=0.1,
)
limits = [
mink.ConfigurationLimit(model),
collision_avoidance_limit,
]
com_mid = model.body("com_target").mocapid[0]
feet_mid = [model.body(f"{foot}_target").mocapid[0] for foot in feet]
hands_mid = [model.body(f"{hand}_target").mocapid[0] for hand in hands]
model = configuration.model
data = configuration.data
solver = "osqp"
with mujoco.viewer.launch_passive(
model=model, data=data, show_left_ui=False, show_right_ui=False
) as viewer:
mujoco.mjv_defaultFreeCamera(model, viewer.cam)
# Initialize to the home keyframe.
configuration.update_from_keyframe("teleop")
posture_task.set_target_from_configuration(configuration)
pelvis_orientation_task.set_target_from_configuration(configuration)
torso_orientation_task.set_target_from_configuration(configuration)
# Initialize mocap bodies at their respective sites.
for hand, foot in zip(hands, feet):
mink.move_mocap_to_frame(model, data, f"{foot}_target", foot, "site")
mink.move_mocap_to_frame(model, data, f"{hand}_target", hand, "site")
data.mocap_pos[com_mid] = data.subtree_com[1]
rate = RateLimiter(frequency=200.0, warn=False)
while viewer.is_running():
# Update task targets.
com_task.set_target(data.mocap_pos[com_mid])
for i, (hand_task, foot_task) in enumerate(zip(hand_tasks, feet_tasks)):
foot_task.set_target(mink.SE3.from_mocap_id(data, feet_mid[i]))
hand_task.set_target(mink.SE3.from_mocap_id(data, hands_mid[i]))
vel = mink.solve_ik(
configuration, tasks, rate.dt, solver, 1e-1, limits=limits
)
configuration.integrate_inplace(vel, rate.dt)
mujoco.mj_camlight(model, data)
# Note the below are optional: they are used to visualize the output of the
# fromto sensor which is used by the collision avoidance constraint.
mujoco.mj_fwdPosition(model, data)
mujoco.mj_sensorPos(model, data)
# Visualize at fixed FPS.
viewer.sync()
rate.sleep()