Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions assets/policies/go1_policy.onnx
Git LFS file not shown
Binary file added assets/robots/go1/assets/hfield.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added assets/robots/go1/assets/rocky_texture.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
304 changes: 304 additions & 0 deletions assets/robots/go1/robot.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,304 @@
<mujoco model="go1 feet only rough terrain scene">
<compiler angle="radian" meshdir="../../../../../mujoco_menagerie/unitree_go1/assets"
autolimits="true" />

<option iterations="1" ls_iterations="5" timestep="0.004" integrator="Euler">
<flag eulerdamp="disable" />
</option>

<custom>
<numeric data="30" name="max_contact_points" />
<numeric data="12" name="max_geom_pairs" />
</custom>

<default>
<default class="go1">
<geom condim="1" />
<joint axis="0 1 0" armature="0.005" damping="0.5" />
<position forcerange="-23.7 23.7" inheritrange="1" kp="35" />
<default class="abduction">
<joint axis="1 0 0" range="-0.863 0.863" frictionloss="0.3" />
</default>
<default class="hip">
<joint range="-0.686 4.501" frictionloss="0.3" />
</default>
<default class="knee">
<joint range="-2.818 -0.888" frictionloss="1.0" />
<position forcerange="-35.55 35.55" />
</default>
<default class="visual">
<geom type="mesh" contype="0" conaffinity="0" group="2" material="dark" />
</default>
<default class="collision">
<geom group="3" type="capsule" />
<default class="hip_left1">
<geom size="0.046 0.02" pos="0 0.045 0" quat="1 1 0 0" type="cylinder" />
</default>
<default class="hip_left2">
<geom size="0.031 0.02" pos="0 0.065 0" quat="1 1 0 0" type="cylinder" />
</default>
<default class="hip_left3">
<geom size="0.046 0.02" quat="1 1 0 0" type="cylinder" />
</default>
<default class="hip_right1">
<geom size="0.046 0.02" pos="0 -0.045 0" quat="1 1 0 0" type="cylinder" />
</default>
<default class="hip_right2">
<geom size="0.031 0.02" pos="0 -0.065 0" quat="1 1 0 0" type="cylinder" />
</default>
<default class="hip_right3">
<geom size="0.046 0.02" quat="1 1 0 0" type="cylinder" />
</default>
<default class="thigh1">
<geom size="0.015" fromto="-0.02 0 0 -0.02 0 -0.16" />
</default>
<default class="thigh2">
<geom size="0.015" fromto="0 0 0 -0.02 0 -0.1" />
</default>
<default class="thigh3">
<geom size="0.015" fromto="-0.02 0 -0.16 0 0 -0.2" />
</default>
<default class="calf1">
<geom size="0.01" fromto="0 0 0 0.02 0 -0.13" />
</default>
<default class="calf2">
<geom size="0.01" fromto="0.02 0 -0.13 0 0 -0.2" />
</default>
<default class="foot">
<geom type="sphere" size="0.023" pos="0 0 -0.213" solimp="0.9 .95 0.023" condim="3" />
</default>
</default>
</default>
</default>

<asset>
<material name="dark" rgba="0.2 0.2 0.2 1" />
<mesh class="go1" file="trunk.stl" />
<mesh class="go1" file="hip.stl" />
<mesh class="go1" file="thigh_mirror.stl" />
<mesh class="go1" file="calf.stl" />
<mesh class="go1" file="thigh.stl" />
</asset>

<worldbody>
<light name="spotlight" mode="targetbodycom" target="trunk" pos="3 0 4" />
<body name="trunk" pos="0 0 0.445" childclass="go1">

<camera name="track" pos="0.846 -1.3 0.316" xyaxes="0.866 0.500 0.000 -0.171 0.296 0.940"
mode="trackcom" />
<camera name="top" pos="-1 0 1" xyaxes="0 -1 0 0.7 0 0.7" mode="trackcom" />
<camera name="side" pos="0 -1 .3" xyaxes="1 0 0 0 1 2" mode="trackcom" />
<camera name="back" pos="-1 0 .3" xyaxes="0 -1 0 1 0 2" mode="trackcom" />
<camera name="head_camera" pos="0.29 0 0.01" xyaxes="0 -1 0 0 0 1" mode="fixed" />
<site name="head" pos="0.3 0 0" rgba="1 0 0 1" size="0.02" group="5" />
<inertial pos="0.0223 0.002 -0.0005" quat="-0.00342088 0.705204 0.000106698 0.708996"
mass="5.204"
diaginertia="0.0716565 0.0630105 0.0168101" />
<freejoint />
<geom class="visual" mesh="trunk" />
<geom class="collision" quat="1 0 1 0" pos="0 -0.04 0" size="0.058 0.125" type="cylinder" />
<geom class="collision" quat="1 0 1 0" pos="0 +0.04 0" size="0.058 0.125" type="cylinder" />
<site name="imu" pos="-0.01592 -0.06659 -0.00617" group="5" />
<body name="FR_hip" pos="0.1881 -0.04675 0">
<inertial pos="-0.0049166 0.00762615 -8.865e-05" quat="0.507341 0.514169 0.495027 0.482891"
mass="0.68"
diaginertia="0.000734064 0.000468438 0.000398719" />
<joint class="abduction" name="FR_hip_joint" />
<geom class="visual" mesh="hip" quat="1 0 0 0" />
<geom name="fr_hip" class="hip_right1" />
<body name="FR_thigh" pos="0 -0.08 0">
<inertial pos="-0.00304722 0.019315 -0.0305004"
quat="0.65243 -0.0272313 0.0775126 0.753383" mass="1.009"
diaginertia="0.00478717 0.00460903 0.000709268" />
<joint class="hip" name="FR_thigh_joint" />
<geom class="visual" mesh="thigh_mirror" />
<geom name="fr_thigh1" class="thigh1" />
<geom name="fr_thigh2" class="thigh2" />
<geom name="fr_thigh3" class="thigh3" />
<body name="FR_calf" pos="0 0 -0.213">
<inertial pos="0.00429862 0.000976676 -0.146197"
quat="0.691246 0.00357467 0.00511118 0.722592"
mass="0.195862" diaginertia="0.00149767 0.00148468 3.58427e-05" />
<joint class="knee" name="FR_calf_joint" />
<geom class="visual" mesh="calf" />
<geom name="fr_calf1" class="calf1" />
<geom name="fr_calf2" class="calf2" />
<geom name="FR" class="foot" />
<site name="FR" pos="0 0 -0.213" type="sphere" size="0.023" group="5" />
</body>
</body>
</body>
<body name="FL_hip" pos="0.1881 0.04675 0">
<inertial pos="-0.0049166 -0.00762615 -8.865e-05" quat="0.482891 0.495027 0.514169 0.507341"
mass="0.68"
diaginertia="0.000734064 0.000468438 0.000398719" />
<joint class="abduction" name="FL_hip_joint" />
<geom class="visual" mesh="hip" />
<geom name="fl_hip" class="hip_left1" />
<body name="FL_thigh" pos="0 0.08 0">
<inertial pos="-0.00304722 -0.019315 -0.0305004"
quat="0.753383 0.0775126 -0.0272313 0.65243" mass="1.009"
diaginertia="0.00478717 0.00460903 0.000709268" />
<joint class="hip" name="FL_thigh_joint" />
<geom class="visual" mesh="thigh" />
<geom name="fl_thigh1" class="thigh1" />
<geom name="fl_thigh2" class="thigh2" />
<geom name="fl_thigh3" class="thigh3" />
<body name="FL_calf" pos="0 0 -0.213">
<inertial pos="0.00429862 0.000976676 -0.146197"
quat="0.691246 0.00357467 0.00511118 0.722592"
mass="0.195862" diaginertia="0.00149767 0.00148468 3.58427e-05" />
<joint class="knee" name="FL_calf_joint" />
<geom class="visual" mesh="calf" />
<geom name="fl_calf1" class="calf1" />
<geom name="fl_calf2" class="calf2" />
<geom name="FL" class="foot" />
<site name="FL" pos="0 0 -0.213" type="sphere" size="0.023" group="5" />
</body>
</body>
</body>
<body name="RR_hip" pos="-0.1881 -0.04675 0">
<inertial pos="0.0049166 0.00762615 -8.865e-05" quat="0.495027 0.482891 0.507341 0.514169"
mass="0.68"
diaginertia="0.000734064 0.000468438 0.000398719" />
<joint class="abduction" name="RR_hip_joint" />
<geom class="visual" quat="0 0 0 -1" mesh="hip" />
<geom name="rr_hip" class="hip_right1" />
<body name="RR_thigh" pos="0 -0.08 0">
<inertial pos="-0.00304722 0.019315 -0.0305004"
quat="0.65243 -0.0272313 0.0775126 0.753383" mass="1.009"
diaginertia="0.00478717 0.00460903 0.000709268" />
<joint class="hip" name="RR_thigh_joint" />
<geom class="visual" mesh="thigh_mirror" />
<geom name="rr_thigh1" class="thigh1" />
<geom name="rr_thigh2" class="thigh2" />
<geom name="rr_thigh3" class="thigh3" />
<body name="RR_calf" pos="0 0 -0.213">
<inertial pos="0.00429862 0.000976676 -0.146197"
quat="0.691246 0.00357467 0.00511118 0.722592"
mass="0.195862" diaginertia="0.00149767 0.00148468 3.58427e-05" />
<joint class="knee" name="RR_calf_joint" />
<geom class="visual" mesh="calf" />
<geom name="rr_calf1" class="calf1" />
<geom name="rr_calf2" class="calf2" />
<geom name="RR" class="foot" />
<site name="RR" pos="0 0 -0.213" type="sphere" size="0.023" group="5" />
</body>
</body>
</body>
<body name="RL_hip" pos="-0.1881 0.04675 0">
<inertial pos="0.0049166 -0.00762615 -8.865e-05" quat="0.514169 0.507341 0.482891 0.495027"
mass="0.68"
diaginertia="0.000734064 0.000468438 0.000398719" />
<joint class="abduction" name="RL_hip_joint" />
<geom class="visual" quat="0 0 1 0" mesh="hip" />
<geom name="rl_hip" class="hip_left1" />
<body name="RL_thigh" pos="0 0.08 0">
<inertial pos="-0.00304722 -0.019315 -0.0305004"
quat="0.753383 0.0775126 -0.0272313 0.65243" mass="1.009"
diaginertia="0.00478717 0.00460903 0.000709268" />
<joint class="hip" name="RL_thigh_joint" />
<geom class="visual" mesh="thigh" />
<geom name="rl_thigh1" class="thigh1" />
<geom name="rl_thigh2" class="thigh2" />
<geom name="rl_thigh3" class="thigh3" />
<body name="RL_calf" pos="0 0 -0.213">
<inertial pos="0.00429862 0.000976676 -0.146197"
quat="0.691246 0.00357467 0.00511118 0.722592"
mass="0.195862" diaginertia="0.00149767 0.00148468 3.58427e-05" />
<joint class="knee" name="RL_calf_joint" />
<geom class="visual" mesh="calf" />
<geom name="rl_calf1" class="calf1" />
<geom name="rl_calf2" class="calf2" />
<geom name="RL" class="foot" />
<site name="RL" pos="0 0 -0.213" type="sphere" size="0.023" group="5" />
</body>
</body>
</body>
</body>
</worldbody>

<actuator>
<position class="abduction" name="FR_hip" joint="FR_hip_joint" />
<position class="hip" name="FR_thigh" joint="FR_thigh_joint" />
<position class="knee" name="FR_calf" joint="FR_calf_joint" />
<position class="abduction" name="FL_hip" joint="FL_hip_joint" />
<position class="hip" name="FL_thigh" joint="FL_thigh_joint" />
<position class="knee" name="FL_calf" joint="FL_calf_joint" />
<position class="abduction" name="RR_hip" joint="RR_hip_joint" />
<position class="hip" name="RR_thigh" joint="RR_thigh_joint" />
<position class="knee" name="RR_calf" joint="RR_calf_joint" />
<position class="abduction" name="RL_hip" joint="RL_hip_joint" />
<position class="hip" name="RL_thigh" joint="RL_thigh_joint" />
<position class="knee" name="RL_calf" joint="RL_calf_joint" />
</actuator>

<sensor>
<gyro site="imu" name="gyro" />
<velocimeter site="imu" name="local_linvel" />
<accelerometer site="imu" name="accelerometer" />
<framepos objtype="site" objname="imu" name="position" />
<framezaxis objtype="site" objname="imu" name="upvector" />
<framexaxis objtype="site" objname="imu" name="forwardvector" />
<framelinvel objtype="site" objname="imu" name="global_linvel" />
<frameangvel objtype="site" objname="imu" name="global_angvel" />
<framequat objtype="site" objname="imu" name="orientation" />
<framelinvel objtype="site" objname="FR" name="FR_global_linvel" />
<framelinvel objtype="site" objname="FL" name="FL_global_linvel" />
<framelinvel objtype="site" objname="RR" name="RR_global_linvel" />
<framelinvel objtype="site" objname="RL" name="RL_global_linvel" />
<framepos objtype="site" objname="FR" name="FR_pos" reftype="site" refname="imu" />
<framepos objtype="site" objname="FL" name="FL_pos" reftype="site" refname="imu" />
<framepos objtype="site" objname="RR" name="RR_pos" reftype="site" refname="imu" />
<framepos objtype="site" objname="RL" name="RL_pos" reftype="site" refname="imu" />
<framepos objtype="site" objname="head" name="head_pos" />

</sensor>

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

<visual>
<rgba force="1 0 0 1" />
<global azimuth="120" elevation="-20" />
<map force="0.01" />
<scale forcewidth="0.3" contactwidth="0.5" contactheight="0.2" />
<quality shadowsize="8192" />
</visual>

<asset>
<!-- https://polyhaven.com/a/rock_face -->
<texture type="2d" name="groundplane" file="assets/rocky_texture.png" />
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5"
reflectance=".8" />
<hfield name="hfield" file="assets/hfield.png" size="10 10 .05 0.1" />
<texture name="skybox" type="skybox" builtin="gradient"
rgb1="0.4 0.6 0.8" rgb2="0.0 0.0 0.0"
width="512" height="512"/>
</asset>

<worldbody>
<geom name="floor" type="hfield" hfield="hfield" material="groundplane" contype="1"
conaffinity="0" priority="1"
friction="1.0" />
<geom name="box" type="box" size="2 2 2" pos="5 0 2" />
<body name="obstacle_cube" pos="1.0 1.6 0.8">
<geom name="cube_geom" type="box" size="1 1 1"
rgba="0.8 0.2 0.2 1.0" mass="1.0"/>
</body>
</worldbody>

<keyframe>
<key name="home"
qpos="
0 0 0.35
1 0 0 0
0.1 0.9 -1.8
-0.1 0.9 -1.8
0.1 0.9 -1.8
-0.1 0.9 -1.8"
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" />
<key name="home_higher"
qpos="0 0 0.35 1 0 0 0 0 0.82 -1.63 0 0.82 -1.63 0 0.82 -1.63 0 0.82 -1.63"
ctrl="0 0.82 -1.63 0 0.82 -1.63 0 0.82 -1.63 0 0.82 -1.63" />
</keyframe>
</mujoco>
Loading