chrisjcc's picture
Minor changes
5df8c16 verified
<mujoco model="tray_sim">
<compiler angle="degree" coordinate="local" inertiafromgeom="true"/>
<option gravity="0 0 -9.81" timestep="0.004" integrator="RK4"/>
<size njmax="1000" nconmax="500"/>
<!-- Contact defaults -->
<default>
<!-- stiffer contact with faster response -->
<!-- reduce compliance smoothing -->
<!-- contact dimensionality — number of contact force directions -->
<!-- defines the collision margin (in meters) -->
<geom
solref="0.001 0.2"
solimp="0.95 0.95 0.001"
condim="4"
margin="0.002"
friction="0.6 0.005 0.0001"
/>
<joint damping="0.2"/> <!-- Damping from pusher for stability (previously set to "0.1") -->
</default>
<visual>
<global offheight="640" offwidth="640"/>
<quality/>
<map zfar="50"/>
</visual>
<asset>
<material name="tray_material" reflectance="0.7" specular="0.3"/>
<material name="obj_material" reflectance="0.5" specular="0.5"/>
<!-- <material name="pusher_material" reflectance="0.2" specular="0.2"/> -->
</asset>
<worldbody>
<!-- Origin marker at world coordinate system -->
<site name="origin_marker" pos="0 0 0" size="0.05" rgba="1 1 0 1"/>
<!-- Lighting -->
<light name="main_light" diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/>
<!-- Camera (isometric top view) -->
<camera name="main_cam" pos="0.5 -0.5 0.4" quat="0.707 0.0 0.707 0.0"/>
<!-- Tilted tray and walls-->
<body name="tray" pos="0 0 0" zaxis="-0.3 0 1">
<!-- Tray floor -->
<geom name="tray_floor" type="box" size="0.3 0.3 0.02"
rgba="0.9 0.9 0.9 1" material="tray_material"
friction="1.0 0.005 0.0001"/>
<!-- Walls -->
<geom type="box" pos="0.0 0.29 0.04" size="0.3 0.01 0.04"
rgba="0.9 0.9 0.9 1" material="tray_material"/>
<geom type="box" pos="0.0 -0.29 0.04" size="0.3 0.01 0.04"
rgba="0.9 0.9 0.9 1" material="tray_material"/>
<geom type="box" pos="0.29 0.0 0.04" size="0.01 0.3 0.04"
rgba="0.9 0.9 0.9 1" material="tray_material"/>
<geom type="box" pos="-0.29 0.0 0.04" size="0.01 0.3 0.04"
rgba="0.9 0.9 0.9 1" material="tray_material"/>
<site name="tray_site" pos="0.1 0.1 0.02" size="0.001"/>
</body>
<!-- Puck (pusher) with lower sliding friction -->
<body name="puck" pos="0.0 0.0 0.05" quat="1 0 0 0">
<geom type="cylinder" size="0.04 0.01"
rgba="1 0 1 1" density="1000" material="obj_material"
friction="0.33 0.005 0.0001"/>
<joint type="free" damping="0.2"/>
<site name="puck_site" pos="0 0 0" size="0.001"/>
</body>
<!-- Objects -->
<!--
<body name="obj0" pos="0.12 -0.18 0.1">
<geom type="box" size="0.015 0.015 0.015" rgba="1 0 0 1" density="1000" material="obj_material"/>
<joint type="free"/>
<site name="obj0_site" pos="0 0 0" size="0.001"/>
</body>
<body name="obj1" pos="-0.07 0.22 0.1">
<geom type="sphere" size="0.015" rgba="0 1 0 1" density="2000" material="obj_material"/>
<joint type="free"/>
</body>
<body name="obj2" pos="0.19 0.03 0.1">
<geom type="box" size="0.015 0.015 0.015" rgba="0 0 1 1" density="1000" material="obj_material"/>
<joint type="free"/>
</body>
<body name="obj3" pos="-0.14 -0.09 0.1">
<geom type="sphere" size="0.015" rgba="1 1 0 1" density="2000" material="obj_material"/>
<joint type="free"/>
</body>
<body name="obj4" pos="0.1 0.2 0.1" quat="1 0 0 0">
<geom type="cylinder" size="0.015 0.03" rgba="1 0 1 1" density="500" material="obj_material"/>
<joint type="free"/>
</body>
<body name="obj5" pos="-0.21 0.08 0.1">
<geom type="sphere" size="0.015" rgba="0 1 1 1" density="2000" material="obj_material"/>
<joint type="free"/>
</body>
<body name="obj6" pos="0.17 -0.12 0.1">
<geom type="box" size="0.015 0.015 0.015" rgba="1 0.5 0 1" density="1000" material="obj_material"/>
<joint type="free"/>
</body>
<body name="obj7" pos="-0.03 -0.20 0.1">
<geom type="sphere" size="0.015" rgba="0.5 0 1 1" density="2000" material="obj_material"/>
<joint type="free"/>
</body>
<body name="obj8" pos="0.24 0.11 0.1">
<geom type="box" size="0.015 0.015 0.015" rgba="0.3 0.8 0.2 1" density="1000" material="obj_material"/>
<joint type="free"/>
</body>
<body name="obj9" pos="-0.16 0.19 0.1">
<geom type="sphere" size="0.015" rgba="0.9 0.3 0.7 1" density="2000" material="obj_material"/>
<joint type="free"/>
</body>
-->
</worldbody>
<!-- Tendon for spring-like behavior (stiffness inference) -->
<!--
<tendon>
<spatial name="spring_obj0" stiffness="100" damping="1.0" width="0.005">
<site site="obj0_site"/>
<site site="tray_site"/>
</spatial>
</tendon>
-->
<keyframe>
<key name="scene" qpos="0 0 0.02 1 0 0 0" qvel="0 0 0 0 1 200" />
</keyframe>
</mujoco>