-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
1 parent
698de14
commit 22a176a
Showing
3 changed files
with
258 additions
and
5 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,174 @@ | ||
<mujoco model="robot"> | ||
<option iterations="50" timestep="0.001" solver="PGS" gravity="0 0 -9.81" /> | ||
|
||
<compiler angle="radian" meshdir="meshes" eulerseq="zyx" autolimits="true" /> | ||
|
||
<default> | ||
<joint limited="true" damping="0.01" armature="0.01" frictionloss="0.01" /> | ||
<geom condim="4" contype="1" conaffinity="15" friction="0.9 0.2 0.2" solref="0.001 2" /> | ||
<motor ctrllimited="true" /> | ||
<equality solref="0.001 2" /> | ||
<default class="visualgeom"> | ||
<geom material="visualgeom" condim="1" contype="0" conaffinity="0" /> | ||
</default> | ||
</default> | ||
|
||
<asset> | ||
<mesh name="trunk" file="trunk.stl" scale="0.001 0.001 0.001" /> | ||
<mesh name="buttock" file="buttock.stl" scale="0.001 0.001 0.001" /> | ||
<mesh name="leg" file="leg.stl" scale="0.001 0.001 0.001" /> | ||
<mesh name="mthigh" file="mthigh.stl" scale="0.001 0.001 0.001" /> | ||
<mesh name="mcalf" file="mcalf.stl" scale="0.001 0.001 0.001" /> | ||
<mesh name="thigh" file="thigh.stl" scale="0.001 0.001 0.001" /> | ||
<mesh name="calf" file="calf.stl" scale="0.001 0.001 0.001" /> | ||
<mesh name="clav" file="clav.stl" scale="0.001 0.001 0.001" /> | ||
<mesh name="scap" file="scap.stl" scale="0.001 0.001 0.001" /> | ||
<mesh name="uarm" file="uarm.stl" scale="0.001 0.001 0.001" /> | ||
<mesh name="farm" file="farm.stl" scale="0.001 0.001 0.001" /> | ||
<texture name="texplane" type="2d" builtin="checker" rgb1=".0 .0 .0" rgb2=".8 .8 .8" width="100" height="100" /> | ||
<material name="matplane" reflectance="0." texture="texplane" texrepeat="1 1" texuniform="true" /> | ||
<material name="visualgeom" rgba="0.5 0.9 0.2 1" /> | ||
</asset> | ||
|
||
<worldbody> | ||
<light directional="true" diffuse="0.4 0.4 0.4" specular="0.1 0.1 0.1" pos="0 0 5.0" dir="0 0 -1" castshadow="false" /> | ||
<light directional="true" diffuse="0.6 0.6 0.6" specular="0.2 0.2 0.2" pos="0 0 4" dir="0 0 -1" /> | ||
<geom name="ground" type="plane" pos="0 0 0" size="100 100 0.001" quat="1 0 0 0" material="matplane" condim="3" conaffinity="15" /> | ||
<camera name="fixed" pos="0 -3.0 1.12" xyaxes="1 0 0 0 0 1" /> | ||
<camera name="track" mode="trackcom" pos="0 -3.0 1.12" xyaxes="1 0 0 0 0 1" /> | ||
<body name="root" pos="0 0 0.63" quat="1 0 0 0"> | ||
<freejoint name="root" /> | ||
<site name="imu" size="0.01" pos="0 0 0" /> | ||
<geom type="mesh" mesh="trunk" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" /> | ||
<geom type="mesh" rgba="1 0.5 0.75 1" mesh="trunk" /> | ||
<geom pos="0 0.255 0.45" quat="2.67949e-08 -1 0 0" type="mesh" mesh="clav" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" /> | ||
<geom type="mesh" rgba="1 0.5 0.75 1" mesh="clav" pos="0 0.255 0.45" quat="2.67949e-08 -1 0 0" /> | ||
<geom pos="0 0.255 0.45" type="mesh" mesh="scap" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" /> | ||
<geom type="mesh" rgba="1 0.5 0.75 1" mesh="scap" pos="0 0.255 0.45" /> | ||
<geom pos="0 0.255 0.45" type="mesh" mesh="uarm" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" /> | ||
<geom type="mesh" rgba="1 0.5 0.75 1" mesh="uarm" pos="0 0.255 0.45" /> | ||
<geom pos="0 0.255 0.22" type="mesh" mesh="farm" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" /> | ||
<geom type="mesh" rgba="1 0.5 0.75 1" mesh="farm" pos="0 0.255 0.22" /> | ||
<geom pos="0 -0.255 0.45" quat="1 0 0 0" type="mesh" mesh="clav" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" /> | ||
<geom type="mesh" rgba="1 0.5 0.75 1" mesh="clav" pos="0 -0.255 0.45" quat="1 0 0 0" /> | ||
<geom pos="0 -0.255 0.45" type="mesh" mesh="scap" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" /> | ||
<geom type="mesh" rgba="1 0.5 0.75 1" mesh="scap" pos="0 -0.255 0.45" /> | ||
<geom pos="0 -0.255 0.45" type="mesh" mesh="uarm" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" /> | ||
<geom type="mesh" rgba="1 0.5 0.75 1" mesh="uarm" pos="0 -0.255 0.45" /> | ||
<geom pos="0 -0.255 0.22" type="mesh" mesh="farm" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" /> | ||
<geom type="mesh" rgba="1 0.5 0.75 1" mesh="farm" pos="0 -0.255 0.22" /> | ||
<body name="L_buttock" pos="0 0.1577 0"> | ||
<inertial pos="0.00129183 -0.00184328 2.27946e-05" quat="0.706341 0.707841 -0.00498313 -0.00434939" mass="1.29909" diaginertia="0.00209325 0.00150009 0.00131174" /> | ||
<joint name="L_hip_y" pos="0 0 0" axis="0 1 0" range="-3.14 3.14" /> | ||
<geom quat="2.67949e-08 1 0 0" type="mesh" mesh="buttock" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" /> | ||
<geom type="mesh" rgba="1 0.5 0.75 1" mesh="buttock" quat="2.67949e-08 1 0 0" /> | ||
<body name="L_leg"> | ||
<inertial pos="0.000708602 -2.24355e-05 -0.110352" quat="0.706876 0.0329943 0.0330587 0.705794" mass="1.33983" diaginertia="0.00375341 0.00352246 0.00184361" /> | ||
<joint name="L_hip_x" pos="0 0 0" axis="1 0 0" range="-0.523 2.093" /> | ||
<geom type="mesh" mesh="leg" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" /> | ||
<geom type="mesh" rgba="1 0.5 0.75 1" mesh="leg" /> | ||
<body name="L_thigh"> | ||
<inertial pos="-0.000407357 0.00130538 -0.291653" quat="0.711843 -0.00549725 0.000501512 0.702317" mass="1.93995" diaginertia="0.00607631 0.0044935 0.00293511" /> | ||
<joint name="L_hip_z" pos="0 0 0" axis="0 0 1" range="-3.14 3.14" /> | ||
<geom type="mesh" mesh="mthigh" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" /> | ||
<geom type="mesh" rgba="1 0.5 0.75 1" mesh="mthigh" /> | ||
<body name="L_calf" pos="0 0 -0.3"> | ||
<inertial pos="-0.00195352 -0.00434338 -0.134048" quat="0.599799 -0.00402307 0.025204 0.799743" mass="1.54477" diaginertia="0.00986297 0.00971929 0.00143814" /> | ||
<joint name="L_knee" pos="0 0 0" axis="0 1 0" range="-1.919 1.919" /> | ||
<geom type="mesh" mesh="mcalf" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" /> | ||
<geom type="mesh" rgba="1 0.5 0.75 1" mesh="mcalf" /> | ||
<body name="L_foot" pos="0 0 -0.3"> | ||
<inertial pos="0.0233665 0.014827 -0.0165314" quat="-0.00182247 0.713608 0.0126839 0.700428" mass="0.542373" diaginertia="0.00215059 0.00196588 0.000256086" /> | ||
<joint name="L_ankle_y" pos="0 0 0" axis="0 1 0" range="-0.698 0.698" frictionloss="0.01" /> | ||
<geom size="0.11 0.04 0.0075" pos="0.03 -0.011 -0.02" type="box" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" /> | ||
<geom type="box" rgba="1 0.5 0.75 1" size="0.11 0.04 0.0075" pos="0.03 -0.011 -0.02" /> | ||
</body> | ||
</body> | ||
</body> | ||
</body> | ||
</body> | ||
<body name="R_buttock" pos="0 -0.1577 0"> | ||
<inertial pos="0.00129183 0.00184328 2.27946e-05" quat="0.707841 0.706341 0.00434939 0.00498313" mass="1.29909" diaginertia="0.00209325 0.00150009 0.00131174" /> | ||
<joint name="R_hip_y" pos="0 0 0" axis="0 1 0" range="-3.14 3.14" /> | ||
<geom type="mesh" mesh="buttock" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" /> | ||
<geom type="mesh" rgba="1 0.5 0.75 1" mesh="buttock" /> | ||
<body name="R_leg"> | ||
<inertial pos="0.000708602 2.24355e-05 -0.110352" quat="0.705794 0.0330587 0.0329943 0.706876" mass="1.33983" diaginertia="0.00375341 0.00352246 0.00184361" /> | ||
<joint name="R_hip_x" pos="0 0 0" axis="1 0 0" range="-2.093 0.523" /> | ||
<geom type="mesh" mesh="leg" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" /> | ||
<geom type="mesh" rgba="1 0.5 0.75 1" mesh="leg" /> | ||
<body name="R_thigh"> | ||
<inertial pos="-0.000407357 -0.00130538 -0.291653" quat="0.702317 0.000501512 -0.00549725 0.711843" mass="1.93995" diaginertia="0.00607631 0.0044935 0.00293511" /> | ||
<joint name="R_hip_z" pos="0 0 0" axis="0 0 1" range="-3.14 3.14" /> | ||
<geom type="mesh" mesh="thigh" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" /> | ||
<geom type="mesh" rgba="1 0.5 0.75 1" mesh="thigh" /> | ||
<body name="R_calf" pos="0 0 -0.3"> | ||
<inertial pos="-0.00195352 0.00434338 -0.134048" quat="0.799743 0.025204 -0.00402307 0.599799" mass="1.54477" diaginertia="0.00986297 0.00971929 0.00143814" /> | ||
<joint name="R_knee" pos="0 0 0" axis="0 1 0" range="-1.919 1.919" /> | ||
<geom type="mesh" mesh="calf" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" /> | ||
<geom type="mesh" rgba="1 0.5 0.75 1" mesh="calf" /> | ||
<body name="R_foot" pos="0 0 -0.3"> | ||
<inertial pos="0.0233665 0.014827 -0.0165314" quat="-0.00182247 0.713608 0.0126839 0.700428" mass="0.542373" diaginertia="0.00215059 0.00196588 0.000256086" /> | ||
<joint name="R_ankle_y" pos="0 0 0" axis="0 1 0" range="-0.698 0.698" frictionloss="0.01" /> | ||
<geom size="0.11 0.04 0.0075" pos="0.03 0.011 -0.02" type="box" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" /> | ||
<geom type="box" rgba="1 0.5 0.75 1" size="0.11 0.04 0.0075" pos="0.03 0.011 -0.02" /> | ||
</body> | ||
</body> | ||
</body> | ||
</body> | ||
</body> | ||
</body> | ||
</worldbody> | ||
|
||
<actuator> | ||
<motor name="L_hip_y" joint="L_hip_y" ctrllimited="true" ctrlrange="-200 200" gear="1" /> | ||
<motor name="L_hip_x" joint="L_hip_x" ctrllimited="true" ctrlrange="-200 200" gear="1" /> | ||
<motor name="L_hip_z" joint="L_hip_z" ctrllimited="true" ctrlrange="-200 200" gear="1" /> | ||
<motor name="L_knee" joint="L_knee" ctrllimited="true" ctrlrange="-200 200" gear="1" /> | ||
<motor name="L_ankle_y" joint="L_ankle_y" ctrllimited="true" ctrlrange="-200 200" gear="1" /> | ||
<motor name="R_hip_y" joint="R_hip_y" ctrllimited="true" ctrlrange="-200 200" gear="1" /> | ||
<motor name="R_hip_x" joint="R_hip_x" ctrllimited="true" ctrlrange="-200 200" gear="1" /> | ||
<motor name="R_hip_z" joint="R_hip_z" ctrllimited="true" ctrlrange="-200 200" gear="1" /> | ||
<motor name="R_knee" joint="R_knee" ctrllimited="true" ctrlrange="-200 200" gear="1" /> | ||
<motor name="R_ankle_y" joint="R_ankle_y" ctrllimited="true" ctrlrange="-200 200" gear="1" /> | ||
</actuator> | ||
|
||
<sensor> | ||
<actuatorpos name="L_hip_y_p" actuator="L_hip_y" user="13" /> | ||
<actuatorvel name="L_hip_y_v" actuator="L_hip_y" user="13" /> | ||
<actuatorfrc name="L_hip_y_f" actuator="L_hip_y" noise="0.001" user="13" /> | ||
<actuatorpos name="L_hip_x_p" actuator="L_hip_x" user="13" /> | ||
<actuatorvel name="L_hip_x_v" actuator="L_hip_x" user="13" /> | ||
<actuatorfrc name="L_hip_x_f" actuator="L_hip_x" noise="0.001" user="13" /> | ||
<actuatorpos name="L_hip_z_p" actuator="L_hip_z" user="13" /> | ||
<actuatorvel name="L_hip_z_v" actuator="L_hip_z" user="13" /> | ||
<actuatorfrc name="L_hip_z_f" actuator="L_hip_z" noise="0.001" user="13" /> | ||
<actuatorpos name="L_knee_p" actuator="L_knee" user="13" /> | ||
<actuatorvel name="L_knee_v" actuator="L_knee" user="13" /> | ||
<actuatorfrc name="L_knee_f" actuator="L_knee" noise="0.001" user="13" /> | ||
<actuatorpos name="L_ankle_y_p" actuator="L_ankle_y" user="13" /> | ||
<actuatorvel name="L_ankle_y_v" actuator="L_ankle_y" user="13" /> | ||
<actuatorfrc name="L_ankle_y_f" actuator="L_ankle_y" noise="0.001" user="13" /> | ||
<actuatorpos name="R_hip_y_p" actuator="R_hip_y" user="13" /> | ||
<actuatorvel name="R_hip_y_v" actuator="R_hip_y" user="13" /> | ||
<actuatorfrc name="R_hip_y_f" actuator="R_hip_y" noise="0.001" user="13" /> | ||
<actuatorpos name="R_hip_x_p" actuator="R_hip_x" user="13" /> | ||
<actuatorvel name="R_hip_x_v" actuator="R_hip_x" user="13" /> | ||
<actuatorfrc name="R_hip_x_f" actuator="R_hip_x" noise="0.001" user="13" /> | ||
<actuatorpos name="R_hip_z_p" actuator="R_hip_z" user="13" /> | ||
<actuatorvel name="R_hip_z_v" actuator="R_hip_z" user="13" /> | ||
<actuatorfrc name="R_hip_z_f" actuator="R_hip_z" noise="0.001" user="13" /> | ||
<actuatorpos name="R_knee_p" actuator="R_knee" user="13" /> | ||
<actuatorvel name="R_knee_v" actuator="R_knee" user="13" /> | ||
<actuatorfrc name="R_knee_f" actuator="R_knee" noise="0.001" user="13" /> | ||
<actuatorpos name="R_ankle_y_p" actuator="R_ankle_y" user="13" /> | ||
<actuatorvel name="R_ankle_y_v" actuator="R_ankle_y" user="13" /> | ||
<actuatorfrc name="R_ankle_y_f" actuator="R_ankle_y" noise="0.001" user="13" /> | ||
<framequat name="orientation" objtype="site" noise="0.001" objname="imu" /> | ||
<gyro name="angular-velocity" site="imu" noise="0.005" cutoff="34.9" /> | ||
</sensor> | ||
|
||
<keyframe> | ||
<key name="default" qpos="0 0 0.63 0. 0.0 0.0 1.0 -0.23 0.0 0.0 0.441 -0.258 -0.23 0.0 0.0 0.441 -0.258" /> | ||
</keyframe> | ||
</mujoco> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.