| |
| <mujoco model='juggler-v1.5'> |
| <compiler inertiafromgeom='auto' angle='radian'/> |
|
|
| <default> |
| <joint limited='true' damping='1' armature='0'/> |
| <geom contype='1' conaffinity='1' condim='3' rgba='0.8 0.6 .4 1' |
| margin="0.001" solref=".02 1" solimp=".8 .8 .01" material="geom" type='capsule'/> |
| <motor ctrlrange='-1 1' ctrllimited='true'/> |
| <default class="passive"> |
| <geom contype='0' conaffinity='0' rgba='.5 .5 1 1' type='capsule' size='.005 .5' /> |
| </default> |
| <default class="wall"> |
| <geom contype='1' conaffinity='1' rgba='1 0 0 1' type='capsule'/> |
| </default> |
| </default> |
|
|
| <option timestep='0.002' iterations="50" solver="PGS"> |
| <flag energy="enable"/> |
| </option> |
|
|
| <visual> |
| <map fogstart="3" fogend="5" force="0.1" znear="0.1"/> |
| <quality shadowsize="2048"/> |
| <global offwidth="800" offheight="800"/> |
| </visual> |
|
|
| <asset> |
| <texture type="skybox" builtin="gradient" width="128" height="128" rgb1=".4 .6 .8" |
| rgb2="0 0 0"/> |
| <texture name="texgeom" type="cube" builtin="flat" mark="cross" width="127" height="1278" |
| rgb1="0.8 0.6 0.4" rgb2="0.8 0.6 0.4" markrgb="1 1 1" random="0.01"/> |
| <texture name="texplane" type="2d" builtin="checker" rgb1=".2 .3 .4" rgb2=".1 0.15 0.2" |
| width="512" height="512"/> |
|
|
| <material name='MatPlane' reflectance='0.5' texture="texplane" texrepeat="1 1" texuniform="true"/> |
| <material name='geom' texture="texgeom" texuniform="true"/> |
| </asset> |
|
|
| |
| |
| <worldbody> |
| <light directional='true' diffuse='.8 .8 .8' specular='0.3 0.3 0.3' pos='0 0 4.0' dir='0 -.15 -1'/> |
| <geom name='floor' pos='0 2 0' size='1 3 .125' type='plane' material="MatPlane" condim='3'/> |
|
|
| <body name='tosser0' pos='0 0 0' euler='0 0 3.14'> |
| <geom pos='0 0 .5' class='passive'/> |
| <body name='hand0' pos='0 0 0'> |
| <geom name='palm0' type='capsule' size='.02' fromto='0 0 .7 0 -.1 .6'/> |
| <geom name='finger0' type='capsule' size='.02' fromto='0 -.1 .6 0 -.15 .6'/> |
| <joint name='wr0_js' type='slide' pos='0 0 .7' axis='0 0 1' range='-.6 .25' damping='10'/> |
| <joint name='wr0_jr' type='hinge' pos='0 0 .7' axis='1 0 0' range='-2.4 0.8'/> |
| </body> |
| </body> |
|
|
| <body name='tosser1' pos='0 1.2 0'> |
| <geom pos='0 0 .5' size='.01 .5' class='passive'/> |
| <body name='hand1' pos='0 0 0'> |
| <geom name='palm1' type='capsule' size='.02' fromto='0 0 .7 0 -.1 .6'/> |
| <geom name='finger1' type='capsule' size='.02' fromto='0 -.1 .6 0 -.15 .6'/> |
| <joint name='wr1_js' type='slide' pos='0 0 .7' axis='0 0 1' range='-.6 .25' damping='10'/> |
| <joint name='wr1_jr' type='hinge' pos='0 0 .7' axis='1 0 0' range='-2.4 0.8'/> |
| </body> |
| </body> |
| |
| <body name='tosser2' pos='0 2 0'> |
| <geom pos='0 0 .5' size='.01 .5' class='passive'/> |
| <body name='hand2' pos='0 0 0'> |
| <geom name='palm2' type='capsule' size='.02' fromto='0 0 .7 0 -.1 .6'/> |
| <geom name='finger2' type='capsule' size='.02' fromto='0 -.1 .6 0 -.15 .6'/> |
| <joint name='wr2_js' type='slide' pos='0 0 .7' axis='0 0 1' range='-.6 .25' damping='10'/> |
| <joint name='wr2_jr' type='hinge' pos='0 0 .7' axis='1 0 0' range='-2.4 0.8'/> |
| </body> |
| </body> |
| |
| <body name='tosser3' pos='0 3 0'> |
| <geom pos='0 0 .5' size='.01 .5' class='passive'/> |
| <body name='hand3' pos='0 0 0'> |
| <geom name='palm3' type='capsule' size='.02' fromto='0 0 .7 0 -.1 .6'/> |
| <geom name='finger3' type='capsule' size='.02' fromto='0 -.1 .6 0 -.15 .6'/> |
| <joint name='wr3_js' type='slide' pos='0 0 .7' axis='0 0 1' range='-.6 .25' damping='10'/> |
| <joint name='wr3_jr' type='hinge' pos='0 0 .7' axis='1 0 0' range='-2.4 0.8'/> |
| </body> |
| </body> |
| |
| |
| <body name='ball' pos='0 .08 1'> |
| <geom name='ball' size='.05' type='sphere'/> |
| <joint name='ballz' type='slide' axis='0 0 1' limited='false' damping='.01'/> |
| <joint name='bally' type='slide' axis='0 1 0' limited='false' damping='.01'/> |
| <joint name='ballx' type='hinge' axis='1 0 0' limited='false' damping='.01'/> |
| </body> |
| |
|
|
| <body name='basket2' pos='0 4 0'> |
| <geom pos='0 -.1 .12' type='capsule' size='.02 .1' rgba='.4 1 .4 1' condim='1' euler='.2 0 0'/> |
| <geom pos='0 .1 .12' type='capsule' size='.02 .1' rgba='.4 1 .4 1' condim='1' euler='-.2 0 0'/> |
| <geom pos='0 0 .02' type='capsule' size='.02 .08' rgba='.4 1 .4 1' condim='1' euler='1.57 0 0'/> |
| <site name='touch' pos='0 0 .03' type='box' group='4' size='.02 .1 .02'/> |
| </body> |
| |
| </worldbody> |
|
|
| <actuator> |
| <motor name='h0a0' gear='35' joint='wr0_js'/> |
| <motor name='h0a1' gear='35' joint='wr0_jr'/> |
| <motor name='h1a0' gear='35' joint='wr1_js'/> |
| <motor name='h1a1' gear='35' joint='wr1_jr'/> |
| <motor name='h2a0' gear='35' joint='wr2_js'/> |
| <motor name='h2a1' gear='35' joint='wr2_jr'/> |
| <motor name='h3a0' gear='35' joint='wr2_js'/> |
| <motor name='h3a1' gear='35' joint='wr2_jr'/> |
| </actuator> |
| |
| <sensor> |
| <jointpos name="Sjp0_wr_js" joint="wr0_js"/> |
| <jointpos name="Sjp0_wr_jr" joint="wr0_jr"/> |
| <jointpos name="Sjp1_wr_js" joint="wr1_js"/> |
| <jointpos name="Sjp1_wr_jr" joint="wr1_jr"/> |
| <jointpos name="Sjp2_wr_js" joint="wr2_js"/> |
| <jointpos name="Sjp2_wr_jr" joint="wr2_jr"/> |
| <jointpos name="Sjp3_wr_js" joint="wr3_js"/> |
| <jointpos name="Sjp3_wr_jr" joint="wr3_jr"/> |
| <touch name="s_touch" site="touch"/> |
| </sensor> |
|
|
| </mujoco> |
|
|