-
Notifications
You must be signed in to change notification settings - Fork 10
/
quadruped_go1.py
76 lines (57 loc) · 2.28 KB
/
quadruped_go1.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
from pathlib import Path
import mujoco
import mujoco.viewer
from loop_rate_limiters import RateLimiter
import mink
_HERE = Path(__file__).parent
_XML = _HERE / "unitree_go1" / "scene.xml"
if __name__ == "__main__":
model = mujoco.MjModel.from_xml_path(_XML.as_posix())
configuration = mink.Configuration(model)
feet = ["FL", "FR", "RR", "RL"]
base_task = mink.FrameTask(
frame_name="trunk",
frame_type="body",
position_cost=1.0,
orientation_cost=1.0,
)
posture_task = mink.PostureTask(model, cost=1e-5)
feet_tasks = []
for foot in feet:
task = mink.FrameTask(
frame_name=foot,
frame_type="site",
position_cost=1.0,
orientation_cost=0.0,
)
feet_tasks.append(task)
tasks = [base_task, posture_task, *feet_tasks]
base_mid = model.body("trunk_target").mocapid[0]
feet_mid = [model.body(f"{foot}_target").mocapid[0] for foot in feet]
model = configuration.model
data = configuration.data
solver = "quadprog"
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("home")
posture_task.set_target_from_configuration(configuration)
# Initialize mocap bodies at their respective sites.
for foot in feet:
mink.move_mocap_to_frame(model, data, f"{foot}_target", foot, "site")
mink.move_mocap_to_frame(model, data, "trunk_target", "trunk", "body")
rate = RateLimiter(frequency=500.0, warn=False)
while viewer.is_running():
# Update task targets.
base_task.set_target(mink.SE3.from_mocap_id(data, base_mid))
for i, task in enumerate(feet_tasks):
task.set_target(mink.SE3.from_mocap_id(data, feet_mid[i]))
# Compute velocity, integrate and set control signal.
vel = mink.solve_ik(configuration, tasks, rate.dt, solver, 1e-5)
configuration.integrate_inplace(vel, rate.dt)
mujoco.mj_camlight(model, data)
# Visualize at fixed FPS.
viewer.sync()
rate.sleep()