|
<mujoco model="swimmer"> |
|
<compiler angle="degree" coordinate="local" inertiafromgeom="true"/> |
|
<option collision="predefined" density="4000" integrator="RK4" timestep="0.01" viscosity="0.1"/> |
|
<default> |
|
<geom conaffinity="1" condim="1" contype="1" material="geom" rgba="0.8 0.6 .4 1"/> |
|
<joint armature='0.1' /> |
|
</default> |
|
<asset> |
|
<texture builtin="gradient" height="100" rgb1="1 1 1" rgb2="0 0 0" type="skybox" width="100"/> |
|
<texture builtin="flat" height="1278" mark="cross" markrgb="1 1 1" name="texgeom" random="0.01" rgb1="0.8 0.6 0.4" rgb2="0.8 0.6 0.4" type="cube" width="127"/> |
|
<texture builtin="checker" height="100" name="texplane" rgb1="0 0 0" rgb2="0.8 0.8 0.8" type="2d" width="100"/> |
|
<material name="MatPlane" reflectance="0.5" shininess="1" specular="1" texrepeat="30 30" texture="texplane"/> |
|
<material name="geom" texture="texgeom" texuniform="true"/> |
|
</asset> |
|
<worldbody> |
|
<light cutoff="100" diffuse="1 1 1" dir="-0 0 -1.3" directional="true" exponent="1" pos="0 0 1.3" specular=".1 .1 .1"/> |
|
<geom conaffinity="1" condim="3" material="MatPlane" name="floor" pos="0 0 -0.1" rgba="0.8 0.9 0.8 1" size="40 40 0.1" type="plane"/> |
|
|
|
<body name="torso" pos="0 0 0"> |
|
<geom density="1000" fromto="1.5 0 0 0.5 0 0" size="0.1" type="capsule"/> |
|
<joint axis="1 0 0" name="slider1" pos="0 0 0" type="slide"/> |
|
<joint axis="0 1 0" name="slider2" pos="0 0 0" type="slide"/> |
|
<joint axis="0 0 1" name="rot" pos="0 0 0" type="hinge"/> |
|
<body name="mid1" pos="0.5 0 0"> |
|
<geom density="1000" fromto="0 0 0 -1 0 0" size="0.1" type="capsule"/> |
|
<joint axis="0 0 1" limited="true" name="rot0" pos="0 0 0" range="-100 100" type="hinge"/> |
|
<body name="mid2" pos="-1 0 0"> |
|
<geom density="1000" fromto="0 0 0 -1 0 0" size="0.1" type="capsule"/> |
|
<joint axis="0 0 -1" limited="true" name="rot1" pos="0 0 0" range="-100 100" type="hinge"/> |
|
<body name="back" pos="-1 0 0"> |
|
<geom density="1000" fromto="0 0 0 -1 0 0" size="0.1" type="capsule"/> |
|
<joint axis="0 0 1" limited="true" name="rot2" pos="0 0 0" range="-100 100" type="hinge"/> |
|
</body> |
|
</body> |
|
</body> |
|
</body> |
|
</worldbody> |
|
<actuator> |
|
<motor ctrllimited="true" ctrlrange="-1 1" gear="150.0" joint="rot0"/> |
|
<motor ctrllimited="true" ctrlrange="-1 1" gear="150.0" joint="rot1"/> |
|
<motor ctrllimited="true" ctrlrange="-1 1" gear="150.0" joint="rot2"/> |
|
</actuator> |
|
</mujoco> |