xmls/tosser.xml (68 lines of code) (raw):

<!-- Author: vikash@openai.com--> <mujoco model='tosser-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"/> <motor ctrlrange='-1 1' ctrllimited='true'/> </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='false' 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 -1 0' size='1.5 3 .125' type='plane' material="MatPlane" condim='3'/> <body name='wall' pos='0 0 0'> <geom name='wall' pos='0 0 .5' size='.02 .5' type='capsule' rgba='.73 .4 .4 1'/> <body name='hand' pos='0 0 0'> <geom name='palm' type='capsule' size='.02' fromto='0 0 .7 0 -.1 .6'/> <geom name='finger' type='capsule' size='.02' fromto='0 -.1 .6 0 -.15 .6'/> <joint name='wr_js' type='slide' pos='0 0 .7' axis='0 0 1' range='-.6 .25' damping='10'/> <joint name='wr_jr' type='hinge' pos='0 0 .7' axis='1 0 0' range='-1.57 0.8'/> </body> </body> <body name='obj' pos='0 -.08 1'> <!--<geom name='obj' type='box' size='.05 .05 0.05'/>--> <!--<geom name='obj' type='sphere' size='.05'/>--> <geom name='obj' type='capsule' size='.05 .075'/> <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='basket1' pos='0 -1 0'> <geom pos='0 -.1 .12' type='capsule' size='.02 .1' rgba='1 .4 .4 1' condim='1' euler='.2 0 0'/> <geom pos='0 .1 .12' type='capsule' size='.02 .1' rgba='1 .4 .4 1' condim='1' euler='-.2 0 0'/> <geom pos='0 0 .02' type='capsule' size='.02 .08' rgba='1 .4 .4 1' condim='1' euler='1.57 0 0'/> <site name='t1' pos='0 0 .03' type='box' group='4' size='.02 .1 .02'/> </body> <body name='basket2' pos='0 -1.5 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='t2' pos='0 0 .03' type='box' group='4' size='.02 .1 .02'/> </body> </worldbody> <actuator> <motor name='a1' gear='35' joint='wr_js'/> <motor name='a2' gear='35' joint='wr_jr' /> </actuator> <sensor> <jointpos name="Sjp_wr_js" joint="wr_js"/> <jointpos name="Sjp_wr_jr" joint="wr_jr"/> <touch name="s_t1" site="t1"/> <touch name="s_t2" site="t2"/> </sensor> </mujoco>