Skip to content

Commit 489cf2d

Browse files
committed
Add sample script
1 parent f00edf2 commit 489cf2d

File tree

3 files changed

+185
-1
lines changed

3 files changed

+185
-1
lines changed

README.md

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@ $ pip install mujoco-python-viewer
2424
import mujoco
2525
import mujoco_viewer
2626

27-
model = mujoco.Mjodel.from_xml_path('humanoid.xml')
27+
model = mujoco.MjModel.from_xml_path('humanoid.xml')
2828
data = mujoco.MjData(model)
2929

3030
# create the viewer object
@@ -34,6 +34,9 @@ viewer = mujoco_viewer.MujocoViewer(model, data)
3434
for _ in range(100000):
3535
mujoco.mj_step(model, data)
3636
viewer.render()
37+
38+
# close
39+
viewer.close()
3740
```
3841

3942
The render should pop up and the simulation should be running.

examples/humanoid.xml

Lines changed: 165 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,165 @@
1+
<!-- Copyright 2021 DeepMind Technologies Limited
2+
3+
Licensed under the Apache License, Version 2.0 (the "License");
4+
you may not use this file except in compliance with the License.
5+
You may obtain a copy of the License at
6+
7+
http://www.apache.org/licenses/LICENSE-2.0
8+
9+
Unless required by applicable law or agreed to in writing, software
10+
distributed under the License is distributed on an "AS IS" BASIS,
11+
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
See the License for the specific language governing permissions and
13+
limitations under the License.
14+
-->
15+
16+
<mujoco model="Humanoid">
17+
<!-- Degree of Freedom: 27
18+
Actuators: 21
19+
20+
This simplified humanoid model, introduced in [1], is designed for bipedal locomotion
21+
behaviours. While several variants of it exist in the wild, this version is based on the model
22+
in the DeepMind Control Suite [2], which has fairly realistic actuator gains.
23+
[1] Synthesis and Stabilization of Complex Behaviors through Online Trajectory Optimization.
24+
https://doi.org/10.1109/IROS.2012.6386025
25+
[2] DeepMind Control Suite, Tassa et al. https://arxiv.org/abs/1801.00690
26+
-->
27+
<option timestep="0.005"/>
28+
29+
<asset>
30+
<texture type="skybox" builtin="gradient" rgb1=".3 .5 .7" rgb2="0 0 0" width="512" height="512"/>
31+
<texture name="body" type="cube" builtin="flat" mark="cross" width="127" height="1278"
32+
rgb1="0.8 0.6 0.4" rgb2="0.8 0.6 0.4" markrgb="1 1 1" random="0.01"/>
33+
<material name="body" texture="body" texuniform="true" rgba="0.8 0.6 .4 1"/>
34+
<texture name="grid" type="2d" builtin="checker" width="512" height="512" rgb1=".1 .2 .3" rgb2=".2 .3 .4"/>
35+
<material name="grid" texture="grid" texrepeat="1 1" texuniform="true" reflectance=".2"/>
36+
</asset>
37+
38+
<default>
39+
<motor ctrlrange="-1 1" ctrllimited="true"/>
40+
<default class="body">
41+
<geom type="capsule" condim="1" friction=".7" solimp=".9 .99 .003" solref=".015 1" material="body"/>
42+
<joint type="hinge" damping=".2" stiffness="1" armature=".01" limited="true" solimplimit="0 .99 .01"/>
43+
<default class="big_joint">
44+
<joint damping="5" stiffness="10"/>
45+
<default class="big_stiff_joint">
46+
<joint stiffness="20"/>
47+
</default>
48+
</default>
49+
</default>
50+
</default>
51+
52+
<visual>
53+
<map force="0.1" zfar="30"/>
54+
<rgba haze="0.15 0.25 0.35 1"/>
55+
<quality shadowsize="4096"/>
56+
<global offwidth="800" offheight="800"/>
57+
</visual>
58+
59+
<worldbody>
60+
<geom name="floor" size="0 0 .05" type="plane" material="grid" condim="3"/>
61+
<light name="spotlight" mode="targetbodycom" target="torso"
62+
diffuse=".8 .8 .8" specular="0.3 0.3 0.3" pos="0 -20 4" cutoff="10"/>
63+
<body name="torso" pos="0 0 1.5" childclass="body">
64+
<light name="top" pos="0 0 2" mode="trackcom"/>
65+
<camera name="back" pos="-3 0 1" xyaxes="0 -1 0 1 0 2" mode="trackcom"/>
66+
<camera name="side" pos="0 -3 1" xyaxes="1 0 0 0 1 2" mode="trackcom"/>
67+
<freejoint name="root"/>
68+
<geom name="torso" fromto="0 -.07 0 0 .07 0" size=".07"/>
69+
<geom name="upper_waist" fromto="-.01 -.06 -.12 -.01 .06 -.12" size=".06"/>
70+
<body name="head" pos="0 0 .19">
71+
<geom name="head" type="sphere" size=".09"/>
72+
<camera name="egocentric" pos=".09 0 0" xyaxes="0 -1 0 .1 0 1" fovy="80"/>
73+
</body>
74+
<body name="lower_waist" pos="-.01 0 -.26">
75+
<geom name="lower_waist" fromto="0 -.06 0 0 .06 0" size=".06"/>
76+
<joint name="abdomen_z" pos="0 0 .065" axis="0 0 1" range="-45 45" class="big_stiff_joint"/>
77+
<joint name="abdomen_y" pos="0 0 .065" axis="0 1 0" range="-75 30" class="big_joint"/>
78+
<body name="pelvis" pos="0 0 -.165">
79+
<joint name="abdomen_x" pos="0 0 .1" axis="1 0 0" range="-35 35" class="big_joint"/>
80+
<geom name="butt" fromto="-.02 -.07 0 -.02 .07 0" size=".09"/>
81+
<body name="right_thigh" pos="0 -.1 -.04">
82+
<joint name="right_hip_x" axis="1 0 0" range="-25 5" class="big_joint"/>
83+
<joint name="right_hip_z" axis="0 0 1" range="-60 35" class="big_joint"/>
84+
<joint name="right_hip_y" axis="0 1 0" range="-110 20" class="big_stiff_joint"/>
85+
<geom name="right_thigh" fromto="0 0 0 0 .01 -.34" size=".06"/>
86+
<body name="right_shin" pos="0 .01 -.403">
87+
<joint name="right_knee" pos="0 0 .02" axis="0 -1 0" range="-160 2"/>
88+
<geom name="right_shin" fromto="0 0 0 0 0 -.3" size=".049"/>
89+
<body name="right_foot" pos="0 0 -.39">
90+
<joint name="right_ankle_y" pos="0 0 .08" axis="0 1 0" range="-50 50" stiffness="6"/>
91+
<joint name="right_ankle_x" pos="0 0 .04" axis="1 0 .5" range="-50 50" stiffness="3"/>
92+
<geom name="right_right_foot" fromto="-.07 -.02 0 .14 -.04 0" size=".027"/>
93+
<geom name="left_right_foot" fromto="-.07 0 0 .14 .02 0" size=".027"/>
94+
</body>
95+
</body>
96+
</body>
97+
<body name="left_thigh" pos="0 .1 -.04">
98+
<joint name="left_hip_x" axis="-1 0 0" range="-25 5" class="big_joint"/>
99+
<joint name="left_hip_z" axis="0 0 -1" range="-60 35" class="big_joint"/>
100+
<joint name="left_hip_y" axis="0 1 0" range="-110 20" class="big_stiff_joint"/>
101+
<geom name="left_thigh" fromto="0 0 0 0 -.01 -.34" size=".06"/>
102+
<body name="left_shin" pos="0 -.01 -.403">
103+
<joint name="left_knee" pos="0 0 .02" axis="0 -1 0" range="-160 2"/>
104+
<geom name="left_shin" fromto="0 0 0 0 0 -.3" size=".049"/>
105+
<body name="left_foot" pos="0 0 -.39">
106+
<joint name="left_ankle_y" pos="0 0 .08" axis="0 1 0" range="-50 50" stiffness="6"/>
107+
<joint name="left_ankle_x" pos="0 0 .04" axis="1 0 .5" range="-50 50" stiffness="3"/>
108+
<geom name="left_left_foot" fromto="-.07 .02 0 .14 .04 0" size=".027"/>
109+
<geom name="right_left_foot" fromto="-.07 0 0 .14 -.02 0" size=".027"/>
110+
</body>
111+
</body>
112+
</body>
113+
</body>
114+
</body>
115+
<body name="right_upper_arm" pos="0 -.17 .06">
116+
<joint name="right_shoulder1" axis="2 1 1" range="-85 60"/>
117+
<joint name="right_shoulder2" axis="0 -1 1" range="-85 60"/>
118+
<geom name="right_upper_arm" fromto="0 0 0 .16 -.16 -.16" size=".04 .16"/>
119+
<body name="right_lower_arm" pos=".18 -.18 -.18">
120+
<joint name="right_elbow" axis="0 -1 1" range="-90 50" stiffness="0"/>
121+
<geom name="right_lower_arm" fromto=".01 .01 .01 .17 .17 .17" size=".031"/>
122+
<body name="right_hand" pos=".18 .18 .18">
123+
<geom name="right_hand" type="sphere" size=".04" zaxis="1 1 1"/>
124+
</body>
125+
</body>
126+
</body>
127+
<body name="left_upper_arm" pos="0 .17 .06">
128+
<joint name="left_shoulder1" axis="2 -1 1" range="-60 85"/>
129+
<joint name="left_shoulder2" axis="0 1 1" range="-60 85"/>
130+
<geom name="left_upper_arm" fromto="0 0 0 .16 .16 -.16" size=".04 .16"/>
131+
<body name="left_lower_arm" pos=".18 .18 -.18">
132+
<joint name="left_elbow" axis="0 -1 -1" range="-90 50" stiffness="0"/>
133+
<geom name="left_lower_arm" fromto=".01 -.01 .01 .17 -.17 .17" size=".031"/>
134+
<body name="left_hand" pos=".18 -.18 .18">
135+
<geom name="left_hand" type="sphere" size=".04" zaxis="1 -1 1"/>
136+
</body>
137+
</body>
138+
</body>
139+
</body>
140+
</worldbody>
141+
142+
<actuator>
143+
<motor name="abdomen_y" gear="40" joint="abdomen_y"/>
144+
<motor name="abdomen_z" gear="40" joint="abdomen_z"/>
145+
<motor name="abdomen_x" gear="40" joint="abdomen_x"/>
146+
<motor name="right_hip_x" gear="40" joint="right_hip_x"/>
147+
<motor name="right_hip_z" gear="40" joint="right_hip_z"/>
148+
<motor name="right_hip_y" gear="120" joint="right_hip_y"/>
149+
<motor name="right_knee" gear="80" joint="right_knee"/>
150+
<motor name="right_ankle_x" gear="20" joint="right_ankle_x"/>
151+
<motor name="right_ankle_y" gear="20" joint="right_ankle_y"/>
152+
<motor name="left_hip_x" gear="40" joint="left_hip_x"/>
153+
<motor name="left_hip_z" gear="40" joint="left_hip_z"/>
154+
<motor name="left_hip_y" gear="120" joint="left_hip_y"/>
155+
<motor name="left_knee" gear="80" joint="left_knee"/>
156+
<motor name="left_ankle_x" gear="20" joint="left_ankle_x"/>
157+
<motor name="left_ankle_y" gear="20" joint="left_ankle_y"/>
158+
<motor name="right_shoulder1" gear="20" joint="right_shoulder1"/>
159+
<motor name="right_shoulder2" gear="20" joint="right_shoulder2"/>
160+
<motor name="right_elbow" gear="40" joint="right_elbow"/>
161+
<motor name="left_shoulder1" gear="20" joint="left_shoulder1"/>
162+
<motor name="left_shoulder2" gear="20" joint="left_shoulder2"/>
163+
<motor name="left_elbow" gear="40" joint="left_elbow"/>
164+
</actuator>
165+
</mujoco>

examples/sample.py

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,16 @@
1+
import mujoco
2+
import mujoco_viewer
3+
4+
model = mujoco.MjModel.from_xml_path('humanoid.xml')
5+
data = mujoco.MjData(model)
6+
7+
# create the viewer object
8+
viewer = mujoco_viewer.MujocoViewer(model, data)
9+
10+
# simulate and render
11+
for _ in range(100000):
12+
mujoco.mj_step(model, data)
13+
viewer.render()
14+
15+
# close
16+
viewer.close()

0 commit comments

Comments
 (0)