Skip to content

Commit ce8933d

Browse files
committed
add go2 fullcollision mjx and rough environment
1 parent 8bc189a commit ce8933d

File tree

8 files changed

+376
-11
lines changed

8 files changed

+376
-11
lines changed

mujoco_playground/_src/locomotion/__init__.py

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -68,6 +68,9 @@
6868
"Go2JoystickFlatTerrain": functools.partial(
6969
go2_joystick.Joystick, task="flat_terrain"
7070
),
71+
"Go2JoystickRoughTerrain": functools.partial(
72+
go2_joystick.Joystick, task="rough_terrain"
73+
),
7174
"H1InplaceGaitTracking": h1_inplace_gait_tracking.InplaceGaitTracking,
7275
"H1JoystickGaitTracking": h1_joystick_gait_tracking.JoystickGaitTracking,
7376
"Op3Joystick": op3_joystick.Joystick,
@@ -102,6 +105,7 @@
102105
"Go1Handstand": go1_handstand.default_config,
103106
"Go1Footstand": go1_handstand.default_config,
104107
"Go2JoystickFlatTerrain": go2_joystick.default_config,
108+
"Go2JoystickRoughTerrain": go2_joystick.default_config,
105109
"H1InplaceGaitTracking": h1_inplace_gait_tracking.default_config,
106110
"H1JoystickGaitTracking": h1_joystick_gait_tracking.default_config,
107111
"Op3Joystick": op3_joystick.default_config,
@@ -127,6 +131,7 @@
127131
"Go1Handstand": go1_randomize.domain_randomize,
128132
"Go1Footstand": go1_randomize.domain_randomize,
129133
"Go2JoystickFlatTerrain": go2_randomize.domain_randomize,
134+
"Go2JoystickRoughTerrain": go2_randomize.domain_randomize,
130135
"T1JoystickFlatTerrain": t1_randomize.domain_randomize,
131136
"T1JoystickRoughTerrain": t1_randomize.domain_randomize,
132137
}

mujoco_playground/_src/locomotion/go2/go2_constants.py

Lines changed: 11 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -19,17 +19,22 @@
1919
from mujoco_playground._src import mjx_env
2020

2121
ROOT_PATH = mjx_env.ROOT_PATH / "locomotion" / "go2"
22-
FLAT_TERRAIN_XML = (
23-
ROOT_PATH / "xmls" / "scene_mjx_flat_terrain.xml"
22+
FEET_ONLY_FLAT_TERRAIN_XML = (
23+
ROOT_PATH / "xmls" / "scene_mjx_feetonly_flat_terrain.xml"
2424
)
25-
ROUGH_TERRAIN_XML = (
26-
ROOT_PATH / "xmls" / "scene_mjx_rough_terrain.xml"
25+
FEET_ONLY_ROUGH_TERRAIN_XML = (
26+
ROOT_PATH / "xmls" / "scene_mjx_feetonly_rough_terrain.xml"
2727
)
28+
FULL_FLAT_TERRAIN_XML = ROOT_PATH / "xmls" / "scene_mjx_flat_terrain.xml"
29+
FULL_COLLISIONS_FLAT_TERRAIN_XML = (
30+
ROOT_PATH / "xmls" / "scene_mjx_fullcollisions_flat_terrain.xml"
31+
)
32+
2833

2934
def task_to_xml(task_name: str) -> epath.Path:
3035
return {
31-
"flat_terrain": FLAT_TERRAIN_XML,
32-
"rough_terrain": ROUGH_TERRAIN_XML,
36+
"flat_terrain": FEET_ONLY_FLAT_TERRAIN_XML,
37+
"rough_terrain": FEET_ONLY_ROUGH_TERRAIN_XML,
3338
}[task_name]
3439

3540

Lines changed: 261 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,261 @@
1+
<mujoco model="go2">
2+
<compiler angle="radian" meshdir="../../../../../mujoco_menagerie/unitree_go2/assets" autolimits="true"/>
3+
4+
<option iterations="1" ls_iterations="5" timestep="0.004" integrator="Euler">
5+
<flag eulerdamp="disable"/>
6+
</option>
7+
8+
<custom>
9+
<numeric data="30" name="max_contact_points"/>
10+
<numeric data="12" name="max_geom_pairs"/>
11+
</custom>
12+
13+
<default>
14+
<default class="go2">
15+
<geom condim="1"/>
16+
<joint axis="0 1 0" damping="2" armature="0.01"/>
17+
<general forcerange="-24 24" biastype="affine" gainprm="50 0 0" biasprm="0 -50 -0.5"/>
18+
19+
<default class="abduction">
20+
<joint axis="1 0 0" range="-1.0472 1.0472"/>
21+
<general ctrlrange="-0.9472 0.9472"/>
22+
</default>
23+
<default class="hip">
24+
<joint range="-1.5708 3.4907"/>
25+
<general ctrlrange="-1.4 2.5"/>
26+
</default>
27+
<default class="knee">
28+
<joint range="-2.7227 -0.83776"/>
29+
<general ctrlrange="-2.6227 -0.84776"/>
30+
</default>
31+
<default class="visual">
32+
<geom type="mesh" contype="0" conaffinity="0" group="2"/>
33+
</default>
34+
<default class="go2foot">
35+
<site pos="0 0 -0.213" type="sphere" size="0.023" group="5"/>
36+
<geom rgba="0.231373 0.380392 0.705882 1"/>
37+
</default>
38+
<default class="collision">
39+
<geom group="3"/>
40+
<default class="foot">
41+
<geom type="sphere" size="0.0175" pos="-0.002 0 -0.213" solimp="0.9 .95 0.023" condim="3"/>
42+
</default>
43+
</default>
44+
</default>
45+
</default>
46+
47+
<asset>
48+
<material name="metal" rgba=".9 .95 .95 1"/>
49+
<material name="black" rgba="0 0 0 1"/>
50+
<material name="white" rgba="1 1 1 1"/>
51+
<material name="gray" rgba="0.671705 0.692426 0.774270 1"/>
52+
53+
<mesh file="base_0.obj"/>
54+
<mesh file="base_1.obj"/>
55+
<mesh file="base_2.obj"/>
56+
<mesh file="base_3.obj"/>
57+
<mesh file="base_4.obj"/>
58+
<mesh file="hip_0.obj"/>
59+
<mesh file="hip_1.obj"/>
60+
<mesh file="thigh_0.obj"/>
61+
<mesh file="thigh_1.obj"/>
62+
<mesh file="thigh_mirror_0.obj"/>
63+
<mesh file="thigh_mirror_1.obj"/>
64+
<mesh file="calf_0.obj"/>
65+
<mesh file="calf_1.obj"/>
66+
<mesh file="calf_mirror_0.obj"/>
67+
<mesh file="calf_mirror_1.obj"/>
68+
<mesh file="foot.obj"/>
69+
</asset>
70+
71+
<worldbody>
72+
<body name="base" pos="0 0 0.445" childclass="go2">
73+
<camera name="track" pos="0.846 -1.465 0.916" xyaxes="0.866 0.500 0.000 -0.171 0.296 0.940" mode="trackcom"/>
74+
<inertial pos="0.021112 0 -0.005366" quat="-0.000543471 0.713435 -0.00173769 0.700719" mass="6.921"
75+
diaginertia="0.107027 0.0980771 0.0244531"/>
76+
<freejoint/>
77+
<geom mesh="base_0" material="black" class="visual"/>
78+
<geom mesh="base_1" material="black" class="visual"/>
79+
<geom mesh="base_2" material="black" class="visual"/>
80+
<geom mesh="base_3" material="white" class="visual"/>
81+
<geom mesh="base_4" material="gray" class="visual"/>
82+
<geom size="0.057 0.04675 0.057" class="collision"/>
83+
<geom size="0.05 0.045" pos="0.285 0 0.01" class="collision"/>
84+
<geom size="0.047" pos="0.293 0 -0.06" class="collision"/>
85+
<site name="imu" pos="-0.02557 0 0.04232"/>
86+
<body name="FL_hip" pos="0.1934 0.0465 0">
87+
<inertial pos="-0.0054 0.00194 -0.000105" quat="0.497014 0.499245 0.505462 0.498237" mass="0.678"
88+
diaginertia="0.00088403 0.000596003 0.000479967"/>
89+
<joint name="FL_hip_joint" class="abduction"/>
90+
<geom mesh="hip_0" material="metal" class="visual"/>
91+
<geom mesh="hip_1" material="gray" class="visual"/>
92+
<geom size="0.046 0.02" pos="0 0.08 0" quat="1 1 0 0" class="collision"/>
93+
<body name="FL_thigh" pos="0 0.0955 0">
94+
<inertial pos="-0.00374 -0.0223 -0.0327" quat="0.829533 0.0847635 -0.0200632 0.551623" mass="1.152"
95+
diaginertia="0.00594973 0.00584149 0.000878787"/>
96+
<joint name="FL_thigh_joint" class="hip"/>
97+
<geom mesh="thigh_0" material="metal" class="visual"/>
98+
<geom mesh="thigh_1" material="gray" class="visual"/>
99+
<geom size="0.017 0.01225 0.017" pos="-0.015 0 -0.1955" quat="0.707107 0 0.707107 0" class="collision"/>
100+
<body name="FL_calf" pos="0 0 -0.213">
101+
<inertial pos="0.00629595 -0.000622121 -0.141417" quat="0.710672 0.00154099 -0.00450087 0.703508"
102+
mass="0.241352" diaginertia="0.0014901 0.00146356 5.31397e-05"/>
103+
<joint name="FL_calf_joint" class="knee"/>
104+
<geom mesh="calf_0" material="gray" class="visual"/>
105+
<geom mesh="calf_1" material="black" class="visual"/>
106+
<geom size="0.012 0.06" pos="0.008 0 -0.06" quat="0.994493 0 -0.104807 0" class="collision"/>
107+
<geom size="0.011 0.0325" pos="0.02 0 -0.148" quat="0.999688 0 0.0249974 0" class="collision"/>
108+
<geom pos="0 0 -0.213" mesh="foot" class="visual" material="black"/>
109+
<geom name="FL" class="foot"/>
110+
<site name="FL" class="go2foot"/>
111+
</body>
112+
</body>
113+
</body>
114+
<body name="FR_hip" pos="0.1934 -0.0465 0">
115+
<inertial pos="-0.0054 -0.00194 -0.000105" quat="0.498237 0.505462 0.499245 0.497014" mass="0.678"
116+
diaginertia="0.00088403 0.000596003 0.000479967"/>
117+
<joint name="FR_hip_joint" class="abduction"/>
118+
<geom mesh="hip_0" material="metal" class="visual" quat="4.63268e-05 1 0 0"/>
119+
<geom mesh="hip_1" material="gray" class="visual" quat="4.63268e-05 1 0 0"/>
120+
<geom size="0.046 0.02" pos="0 -0.08 0" quat="0.707107 0.707107 0 0" class="collision"/>
121+
<body name="FR_thigh" pos="0 -0.0955 0">
122+
<inertial pos="-0.00374 0.0223 -0.0327" quat="0.551623 -0.0200632 0.0847635 0.829533" mass="1.152"
123+
diaginertia="0.00594973 0.00584149 0.000878787"/>
124+
<joint name="FR_thigh_joint" class="hip"/>
125+
<geom mesh="thigh_mirror_0" material="metal" class="visual"/>
126+
<geom mesh="thigh_mirror_1" material="gray" class="visual"/>
127+
<geom size="0.017 0.01225 0.017" pos="-0.015 0 -0.1955" quat="0.707107 0 0.707107 0" class="collision"/>
128+
<body name="FR_calf" pos="0 0 -0.213">
129+
<inertial pos="0.00629595 0.000622121 -0.141417" quat="0.703508 -0.00450087 0.00154099 0.710672"
130+
mass="0.241352" diaginertia="0.0014901 0.00146356 5.31397e-05"/>
131+
<joint name="FR_calf_joint" class="knee"/>
132+
<geom mesh="calf_mirror_0" material="gray" class="visual"/>
133+
<geom mesh="calf_mirror_1" material="black" class="visual"/>
134+
<geom size="0.013 0.06" pos="0.01 0 -0.06" quat="0.995004 0 -0.0998334 0" class="collision"/>
135+
<geom size="0.011 0.0325" pos="0.02 0 -0.148" quat="0.999688 0 0.0249974 0" class="collision"/>
136+
<geom pos="0 0 -0.213" mesh="foot" class="visual" material="black"/>
137+
<geom name="FR" class="foot"/>
138+
<site name="FR" class="go2foot"/>
139+
</body>
140+
</body>
141+
</body>
142+
<body name="RL_hip" pos="-0.1934 0.0465 0">
143+
<inertial pos="0.0054 0.00194 -0.000105" quat="0.505462 0.498237 0.497014 0.499245" mass="0.678"
144+
diaginertia="0.00088403 0.000596003 0.000479967"/>
145+
<joint name="RL_hip_joint" class="abduction"/>
146+
<geom mesh="hip_0" material="metal" class="visual" quat="4.63268e-05 0 1 0"/>
147+
<geom mesh="hip_1" material="gray" class="visual" quat="4.63268e-05 0 1 0"/>
148+
<geom size="0.046 0.02" pos="0 0.08 0" quat="0.707107 0.707107 0 0" class="collision"/>
149+
<body name="RL_thigh" pos="0 0.0955 0">
150+
<inertial pos="-0.00374 -0.0223 -0.0327" quat="0.829533 0.0847635 -0.0200632 0.551623" mass="1.152"
151+
diaginertia="0.00594973 0.00584149 0.000878787"/>
152+
<joint name="RL_thigh_joint" class="hip"/>
153+
<geom mesh="thigh_0" material="metal" class="visual"/>
154+
<geom mesh="thigh_1" material="gray" class="visual"/>
155+
<geom size="0.017 0.01225 0.017" pos="-0.015 0 -0.1955" quat="0.707107 0 0.707107 0" class="collision"/>
156+
<body name="RL_calf" pos="0 0 -0.213">
157+
<inertial pos="0.00629595 -0.000622121 -0.141417" quat="0.710672 0.00154099 -0.00450087 0.703508"
158+
mass="0.241352" diaginertia="0.0014901 0.00146356 5.31397e-05"/>
159+
<joint name="RL_calf_joint" class="knee"/>
160+
<geom mesh="calf_0" material="gray" class="visual"/>
161+
<geom mesh="calf_1" material="black" class="visual"/>
162+
<geom size="0.013 0.06" pos="0.01 0 -0.06" quat="0.995004 0 -0.0998334 0" class="collision"/>
163+
<geom size="0.011 0.0325" pos="0.02 0 -0.148" quat="0.999688 0 0.0249974 0" class="collision"/>
164+
<geom pos="0 0 -0.213" mesh="foot" class="visual" material="black"/>
165+
<geom name="RL" class="foot"/>
166+
<site name="RL" class="go2foot"/>
167+
</body>
168+
</body>
169+
</body>
170+
<body name="RR_hip" pos="-0.1934 -0.0465 0">
171+
<inertial pos="0.0054 -0.00194 -0.000105" quat="0.499245 0.497014 0.498237 0.505462" mass="0.678"
172+
diaginertia="0.00088403 0.000596003 0.000479967"/>
173+
<joint name="RR_hip_joint" class="abduction"/>
174+
<geom mesh="hip_0" material="metal" class="visual" quat="2.14617e-09 4.63268e-05 4.63268e-05 -1"/>
175+
<geom mesh="hip_1" material="gray" class="visual" quat="2.14617e-09 4.63268e-05 4.63268e-05 -1"/>
176+
<geom size="0.046 0.02" pos="0 -0.08 0" quat="0.707107 0.707107 0 0" class="collision"/>
177+
<body name="RR_thigh" pos="0 -0.0955 0">
178+
<inertial pos="-0.00374 0.0223 -0.0327" quat="0.551623 -0.0200632 0.0847635 0.829533" mass="1.152"
179+
diaginertia="0.00594973 0.00584149 0.000878787"/>
180+
<joint name="RR_thigh_joint" class="hip"/>
181+
<geom mesh="thigh_mirror_0" material="metal" class="visual"/>
182+
<geom mesh="thigh_mirror_1" material="gray" class="visual"/>
183+
<geom size="0.017 0.01225 0.017" pos="-0.015 0 -0.1955" quat="0.707107 0 0.707107 0" class="collision"/>
184+
<body name="RR_calf" pos="0 0 -0.213">
185+
<inertial pos="0.00629595 0.000622121 -0.141417" quat="0.703508 -0.00450087 0.00154099 0.710672"
186+
mass="0.241352" diaginertia="0.0014901 0.00146356 5.31397e-05"/>
187+
<joint name="RR_calf_joint" class="knee"/>
188+
<geom mesh="calf_mirror_0" material="gray" class="visual"/>
189+
<geom mesh="calf_mirror_1" material="black" class="visual"/>
190+
<geom size="0.013 0.06" pos="0.01 0 -0.06" quat="0.995004 0 -0.0998334 0" class="collision"/>
191+
<geom size="0.011 0.0325" pos="0.02 0 -0.148" quat="0.999688 0 0.0249974 0" class="collision"/>
192+
<geom pos="0 0 -0.213" mesh="foot" class="visual" material="black"/>
193+
<geom name="RR" class="foot"/>
194+
<site name="RR" class="go2foot"/>
195+
</body>
196+
</body>
197+
</body>
198+
</body>
199+
</worldbody>
200+
201+
<actuator>
202+
<general class="abduction" name="FL_hip" joint="FL_hip_joint"/>
203+
<general class="hip" name="FL_thigh" joint="FL_thigh_joint"/>
204+
<general class="knee" name="FL_calf" joint="FL_calf_joint"/>
205+
<general class="abduction" name="FR_hip" joint="FR_hip_joint"/>
206+
<general class="hip" name="FR_thigh" joint="FR_thigh_joint"/>
207+
<general class="knee" name="FR_calf" joint="FR_calf_joint"/>
208+
<general class="abduction" name="RL_hip" joint="RL_hip_joint"/>
209+
<general class="hip" name="RL_thigh" joint="RL_thigh_joint"/>
210+
<general class="knee" name="RL_calf" joint="RL_calf_joint"/>
211+
<general class="abduction" name="RR_hip" joint="RR_hip_joint"/>
212+
<general class="hip" name="RR_thigh" joint="RR_thigh_joint"/>
213+
<general class="knee" name="RR_calf" joint="RR_calf_joint"/>
214+
</actuator>
215+
216+
<sensor>
217+
<jointpos joint="FL_hip_joint" name="abduction_front_left_pos"/>
218+
<jointpos joint="FL_thigh_joint" name="hip_front_left_pos"/>
219+
<jointpos joint="FL_calf_joint" name="knee_front_left_pos"/>
220+
<jointpos joint="RL_hip_joint" name="abduction_hind_left_pos"/>
221+
<jointpos joint="RL_thigh_joint" name="hip_hind_left_pos"/>
222+
<jointpos joint="RL_calf_joint" name="knee_hind_left_pos"/>
223+
<jointpos joint="FR_hip_joint" name="abduction_front_right_pos"/>
224+
<jointpos joint="FR_thigh_joint" name="hip_front_right_pos"/>
225+
<jointpos joint="FR_calf_joint" name="knee_front_right_pos"/>
226+
<jointpos joint="RR_hip_joint" name="abduction_hind_right_pos"/>
227+
<jointpos joint="RR_thigh_joint" name="hip_hind_right_pos"/>
228+
<jointpos joint="RR_calf_joint" name="knee_hind_right_pos"/>
229+
<jointvel joint="FL_hip_joint" name="abduction_front_left_vel"/>
230+
<jointvel joint="FL_thigh_joint" name="hip_front_left_vel"/>
231+
<jointvel joint="FL_calf_joint" name="knee_front_left_vel"/>
232+
<jointvel joint="RL_hip_joint" name="abduction_hind_left_vel"/>
233+
<jointvel joint="RL_thigh_joint" name="hip_hind_left_vel"/>
234+
<jointvel joint="RL_calf_joint" name="knee_hind_left_vel"/>
235+
<jointvel joint="FR_hip_joint" name="abduction_front_right_vel"/>
236+
<jointvel joint="FR_thigh_joint" name="hip_front_right_vel"/>
237+
<jointvel joint="FR_calf_joint" name="knee_front_right_vel"/>
238+
<jointvel joint="RR_hip_joint" name="abduction_hind_right_vel"/>
239+
<jointvel joint="RR_thigh_joint" name="hip_hind_right_vel"/>
240+
<jointvel joint="RR_calf_joint" name="knee_hind_right_vel"/>
241+
242+
<gyro site="imu" name="gyro"/>
243+
<accelerometer site="imu" name="accelerometer"/>
244+
<velocimeter site="imu" name="local_linvel"/>
245+
<framezaxis objtype="site" objname="imu" name="upvector"/>
246+
<framequat objtype="site" objname="imu" name="orientation"/>
247+
<framepos objtype="site" objname="imu" name="global_position"/>
248+
<framelinvel objtype="site" objname="imu" name="global_linvel"/>
249+
<frameangvel objtype="site" objname="imu" name="global_angvel"/>
250+
251+
<framelinvel objtype="site" objname="FR" name="FR_global_linvel"/>
252+
<framelinvel objtype="site" objname="FL" name="FL_global_linvel"/>
253+
<framelinvel objtype="site" objname="RR" name="RR_global_linvel"/>
254+
<framelinvel objtype="site" objname="RL" name="RL_global_linvel"/>
255+
256+
<framepos objtype="site" objname="FR" name="FR_pos" reftype="site" refname="imu"/>
257+
<framepos objtype="site" objname="FL" name="FL_pos" reftype="site" refname="imu"/>
258+
<framepos objtype="site" objname="RR" name="RR_pos" reftype="site" refname="imu"/>
259+
<framepos objtype="site" objname="RL" name="RL_pos" reftype="site" refname="imu"/>
260+
</sensor>
261+
</mujoco>
Lines changed: 47 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,47 @@
1+
<mujoco model="go2 feet only flat terrain scene">
2+
<include file="go2_mjx_feetonly.xml"/>
3+
4+
<statistic center="0 0 0.1" extent="0.8" meansize="0.04"/>
5+
6+
<visual>
7+
<headlight diffuse=".8 .8 .8" ambient=".2 .2 .2" specular="1 1 1"/>
8+
<rgba force="1 0 0 1"/>
9+
<global azimuth="120" elevation="-20"/>
10+
<map force="0.01"/>
11+
<scale forcewidth="0.3" contactwidth="0.5" contactheight="0.2"/>
12+
<quality shadowsize="8192"/>
13+
</visual>
14+
15+
<asset>
16+
<texture type="skybox" builtin="gradient" rgb1="1 1 1" rgb2="1 1 1" width="800" height="800"/>
17+
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="1 1 1" rgb2="1 1 1" markrgb="0 0 0"
18+
width="300" height="300"/>
19+
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0"/>
20+
</asset>
21+
22+
<worldbody>
23+
<geom name="floor" size="0 0 0.01" type="plane" material="groundplane" priority="1" friction="0.6" condim="3" contype="1" conaffinity="0"/>
24+
</worldbody>
25+
26+
<keyframe>
27+
<key name="home" qpos="
28+
0 0 0.278
29+
1 0 0 0
30+
0.1 0.9 -1.8
31+
-0.1 0.9 -1.8
32+
0.1 0.9 -1.8
33+
-0.1 0.9 -1.8"
34+
ctrl="0.1 0.9 -1.8 -0.1 0.9 -1.8 0.1 0.9 -1.8 -0.1 0.9 -1.8"/>
35+
<key name="home_higher" qpos="0 0 0.31 1 0 0 0 0 0.82 -1.63 0 0.82 -1.63 0 0.82 -1.63 0 0.82 -1.63"
36+
ctrl="0 0.82 -1.63 0 0.82 -1.63 0 0.82 -1.63 0 0.82 -1.63"/>
37+
<key name="pre_recovery"
38+
qpos="-0.0318481 -0.000215369 0.0579031 1 -2.70738e-05 6.06169e-05 0.000231261 -0.352275 1.18554 -2.80738 0.360892 1.1806 -2.80281 -0.381197 1.16812 -2.79123 0.391054 1.1622 -2.78576"
39+
ctrl="-0.352275 1.18554 -2.80738 0.360892 1.1806 -2.80281 -0.381197 1.16812 -2.79123 0.391054 1.1622 -2.78576"/>
40+
<key name="footstand"
41+
qpos="0 0 0.54 0.8 0 -0.8 0 0 0.82 -1.6 0 0.82 -1.68 0 1.82 -1.16 0.0 1.82 -1.16"
42+
ctrl="0 0.82 -1.6 0 0.82 -1.68 0 1.82 -1.16 0.0 1.82 -1.16"/>
43+
<key name="handstand"
44+
qpos="0 0 0.54 0.8 0 0.8 0 0 -0.686 -1.16 0 -0.686 -1.16 0 1.7 -1.853 0 1.7 -1.853"
45+
ctrl="0 -0.686 -1.16 0 -0.686 -1.16 0 1.7 -1.853 0 1.7 -1.853"/>
46+
</keyframe>
47+
</mujoco>

mujoco_playground/_src/locomotion/go2/xmls/scene_mjx_rough_terrain.xml renamed to mujoco_playground/_src/locomotion/go2/xmls/scene_mjx_feetonly_rough_terrain.xml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
1-
<mujoco model="go2 rough terrain scene">
2-
<include file="go2_mjx.xml"/>
1+
<mujoco model="go2 feetonly rough terrain scene">
2+
<include file="go2_mjx_feetonly.xml"/>
33

44
<statistic center="0 0 0.1" extent="0.8" meansize="0.04"/>
55

mujoco_playground/_src/locomotion/go2/xmls/scene_mjx_flat_terrain.xml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
1-
<mujoco model="go2 flat terrain scene">
2-
<include file="go2_mjx_feetonly.xml"/>
1+
<mujoco model="go2 scene">
2+
<include file="go2_mjx.xml"/>
33

44
<statistic center="0 0 0.1" extent="0.8" meansize="0.04"/>
55

0 commit comments

Comments
 (0)