nova-sim / robots /ur5 /model /scene.xml
Georg
Enhance homing functionality and client management in mujoco_server.py
0551bb3
<mujoco model="ur5e_with_gripper">
<compiler angle="radian" meshdir="assets" autolimits="true"/>
<option integrator="implicitfast" cone="elliptic" impratio="10"/>
<!-- Wandelbots Corporate Design Colors:
Primary Dark: #01040f (0.004, 0.016, 0.059)
Light/Secondary: #bcbeec (0.737, 0.745, 0.925)
Accent: #211c44 (0.129, 0.110, 0.267)
Highlight: #8b7fef (0.545, 0.498, 0.937)
-->
<visual>
<headlight diffuse="0.6 0.6 0.6" ambient="0.35 0.35 0.4" specular="0 0 0"/>
<rgba haze="0.02 0.04 0.12 1"/>
<global azimuth="120" elevation="-20"/>
</visual>
<asset>
<!-- Wandelbots gradient skybox - deep purple to near black -->
<texture type="skybox" builtin="gradient" rgb1="0.13 0.11 0.27" rgb2="0.004 0.016 0.059" width="512" height="3072"/>
<!-- Ground with Wandelbots purple accent -->
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.08 0.07 0.15" rgb2="0.04 0.04 0.08"
markrgb="0.55 0.5 0.94" width="300" height="300"/>
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.15"/>
<!-- Table with subtle purple tint -->
<material name="table" rgba="0.18 0.16 0.25 1" specular="0.4" shininess="0.4"/>
<!-- Target marker with Wandelbots highlight color -->
<material name="target_mat" rgba="0.55 0.5 0.94 0.6" specular="0.5" shininess="0.5"/>
<!-- UR5e materials - with Wandelbots accent colors -->
<material name="black" rgba="0.02 0.02 0.04 1" specular="0.5" shininess="0.25"/>
<material name="jointgray" rgba="0.22 0.22 0.26 1" specular="0.5" shininess="0.25"/>
<material name="linkgray" rgba="0.74 0.75 0.82 1" specular="0.5" shininess="0.25"/>
<!-- Wandelbots purple accent instead of UR blue -->
<material name="urblue" rgba="0.55 0.5 0.94 1" specular="0.6" shininess="0.35"/>
<!-- Gripper materials -->
<material name="metal" rgba="0.58 0.58 0.58 1"/>
<material name="silicone" rgba="0.1882 0.1882 0.1882 1"/>
<material name="gray" rgba="0.4627 0.4627 0.4627 1"/>
<!-- UR5e meshes -->
<mesh file="base_0.obj"/>
<mesh file="base_1.obj"/>
<mesh file="shoulder_0.obj"/>
<mesh file="shoulder_1.obj"/>
<mesh file="shoulder_2.obj"/>
<mesh file="upperarm_0.obj"/>
<mesh file="upperarm_1.obj"/>
<mesh file="upperarm_2.obj"/>
<mesh file="upperarm_3.obj"/>
<mesh file="forearm_0.obj"/>
<mesh file="forearm_1.obj"/>
<mesh file="forearm_2.obj"/>
<mesh file="forearm_3.obj"/>
<mesh file="wrist1_0.obj"/>
<mesh file="wrist1_1.obj"/>
<mesh file="wrist1_2.obj"/>
<mesh file="wrist2_0.obj"/>
<mesh file="wrist2_1.obj"/>
<mesh file="wrist2_2.obj"/>
<mesh file="wrist3.obj"/>
<!-- Gripper meshes -->
<mesh name="base_mount" file="base_mount.stl" scale="0.001 0.001 0.001"/>
<mesh name="base_g" file="base.stl" scale="0.001 0.001 0.001"/>
<mesh name="driver" file="driver.stl" scale="0.001 0.001 0.001"/>
<mesh name="coupler" file="coupler.stl" scale="0.001 0.001 0.001"/>
<mesh name="follower" file="follower.stl" scale="0.001 0.001 0.001"/>
<mesh name="pad" file="pad.stl" scale="0.001 0.001 0.001"/>
<mesh name="silicone_pad" file="silicone_pad.stl" scale="0.001 0.001 0.001"/>
<mesh name="spring_link" file="spring_link.stl" scale="0.001 0.001 0.001"/>
</asset>
<default>
<default class="ur5e">
<joint axis="0 1 0" range="-6.28319 6.28319" armature="0.1"/>
<general gaintype="fixed" biastype="affine" ctrlrange="-6.2831 6.2831" gainprm="2000" biasprm="0 -2000 -400" forcerange="-150 150"/>
<default class="size3">
<default class="size3_limited">
<joint range="-3.1415 3.1415"/>
<general ctrlrange="-3.1415 3.1415"/>
</default>
</default>
<default class="size1">
<general gainprm="500" biasprm="0 -500 -100" forcerange="-28 28"/>
</default>
<default class="visual">
<geom type="mesh" contype="0" conaffinity="0" group="2"/>
</default>
<default class="collision">
<geom type="capsule" group="3"/>
<default class="eef_collision">
<geom type="cylinder"/>
</default>
</default>
<site size="0.001" rgba="0.5 0.5 0.5 0.3" group="4"/>
</default>
<default class="gripper">
<general biastype="affine"/>
<joint axis="1 0 0"/>
<default class="driver_j">
<joint range="0 0.8" armature="0.005" damping="0.1" solimplimit="0.95 0.99 0.001" solreflimit="0.005 1"/>
</default>
<default class="follower_j">
<joint range="-0.872664 0.872664" armature="0.001" pos="0 -0.018 0.0065" solimplimit="0.95 0.99 0.001" solreflimit="0.005 1"/>
</default>
<default class="spring_link_j">
<joint range="-0.29670597283 0.8" armature="0.001" stiffness="0.05" springref="2.62" damping="0.00125"/>
</default>
<default class="coupler_j">
<joint range="-1.57 0" armature="0.001" solimplimit="0.95 0.99 0.001" solreflimit="0.005 1"/>
</default>
<default class="visual_g">
<geom type="mesh" contype="0" conaffinity="0" group="2"/>
</default>
<default class="collision_g">
<geom type="mesh" group="3"/>
<default class="pad_box1">
<geom mass="0" type="box" pos="0 -0.0026 0.028125" size="0.011 0.004 0.009375" friction="0.7"
solimp="0.95 0.99 0.001" solref="0.004 1" priority="1" rgba="0.55 0.55 0.55 1"/>
</default>
<default class="pad_box2">
<geom mass="0" type="box" pos="0 -0.0026 0.009375" size="0.011 0.004 0.009375" friction="0.6"
solimp="0.95 0.99 0.001" solref="0.004 1" priority="1" rgba="0.45 0.45 0.45 1"/>
</default>
</default>
</default>
</default>
<worldbody>
<light pos="0 0 3.5" dir="0 0 -1" directional="true"/>
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
<!-- Table -->
<body name="table" pos="0 0 0">
<geom name="table_top" type="box" pos="0.5 0 0.4" size="0.4 0.6 0.02" material="table"/>
<geom name="table_leg1" type="box" pos="0.2 0.4 0.2" size="0.03 0.03 0.2" material="table"/>
<geom name="table_leg2" type="box" pos="0.2 -0.4 0.2" size="0.03 0.03 0.2" material="table"/>
<geom name="table_leg3" type="box" pos="0.8 0.4 0.2" size="0.03 0.03 0.2" material="table"/>
<geom name="table_leg4" type="box" pos="0.8 -0.4 0.2" size="0.03 0.03 0.2" material="table"/>
</body>
<!-- Target visualization sphere (for IK target) -->
<body name="target" pos="0.4 0.0 0.6" mocap="true">
<geom name="target_vis" type="sphere" size="0.03" material="target_mat" contype="0" conaffinity="0"/>
</body>
<!-- UR5e robot mounted on table edge -->
<body name="base" pos="0 0 0.42" quat="0 0 0 -1" childclass="ur5e">
<inertial mass="4.0" pos="0 0 0" diaginertia="0.00443333156 0.00443333156 0.0072"/>
<geom mesh="base_0" material="black" class="visual"/>
<geom mesh="base_1" material="jointgray" class="visual"/>
<body name="shoulder_link" pos="0 0 0.163">
<inertial mass="3.7" pos="0 0 0" diaginertia="0.0102675 0.0102675 0.00666"/>
<joint name="shoulder_pan_joint" class="size3" axis="0 0 1"/>
<geom mesh="shoulder_0" material="urblue" class="visual"/>
<geom mesh="shoulder_1" material="black" class="visual"/>
<geom mesh="shoulder_2" material="jointgray" class="visual"/>
<geom class="collision" size="0.06 0.06" pos="0 0 -0.04"/>
<body name="upper_arm_link" pos="0 0.138 0" quat="1 0 1 0">
<inertial mass="8.393" pos="0 0 0.2125" diaginertia="0.133886 0.133886 0.0151074"/>
<joint name="shoulder_lift_joint" class="size3"/>
<geom mesh="upperarm_0" material="linkgray" class="visual"/>
<geom mesh="upperarm_1" material="black" class="visual"/>
<geom mesh="upperarm_2" material="jointgray" class="visual"/>
<geom mesh="upperarm_3" material="urblue" class="visual"/>
<geom class="collision" pos="0 -0.04 0" quat="1 1 0 0" size="0.06 0.06"/>
<geom class="collision" size="0.05 0.2" pos="0 0 0.2"/>
<body name="forearm_link" pos="0 -0.131 0.425">
<inertial mass="2.275" pos="0 0 0.196" diaginertia="0.0311796 0.0311796 0.004095"/>
<joint name="elbow_joint" class="size3_limited"/>
<geom mesh="forearm_0" material="urblue" class="visual"/>
<geom mesh="forearm_1" material="linkgray" class="visual"/>
<geom mesh="forearm_2" material="black" class="visual"/>
<geom mesh="forearm_3" material="jointgray" class="visual"/>
<geom class="collision" pos="0 0.08 0" quat="1 1 0 0" size="0.055 0.06"/>
<geom class="collision" size="0.038 0.19" pos="0 0 0.2"/>
<body name="wrist_1_link" pos="0 0 0.392" quat="1 0 1 0">
<inertial mass="1.219" pos="0 0.127 0" diaginertia="0.0025599 0.0025599 0.0021942"/>
<joint name="wrist_1_joint" class="size1"/>
<geom mesh="wrist1_0" material="black" class="visual"/>
<geom mesh="wrist1_1" material="urblue" class="visual"/>
<geom mesh="wrist1_2" material="jointgray" class="visual"/>
<geom class="collision" pos="0 0.05 0" quat="1 1 0 0" size="0.04 0.07"/>
<body name="wrist_2_link" pos="0 0.127 0">
<inertial mass="1.219" pos="0 0 0.1" diaginertia="0.0025599 0.0025599 0.0021942"/>
<joint name="wrist_2_joint" axis="0 0 1" class="size1"/>
<geom mesh="wrist2_0" material="black" class="visual"/>
<geom mesh="wrist2_1" material="urblue" class="visual"/>
<geom mesh="wrist2_2" material="jointgray" class="visual"/>
<geom class="collision" size="0.04 0.06" pos="0 0 0.04"/>
<geom class="collision" pos="0 0.02 0.1" quat="1 1 0 0" size="0.04 0.04"/>
<body name="wrist_3_link" pos="0 0 0.1">
<inertial mass="0.1889" pos="0 0.0771683 0" quat="1 0 0 1"
diaginertia="0.000132134 9.90863e-05 9.90863e-05"/>
<joint name="wrist_3_joint" class="size1"/>
<geom material="linkgray" mesh="wrist3" class="visual"/>
<geom class="eef_collision" pos="0 0.08 0" quat="1 1 0 0" size="0.04 0.02"/>
<site name="attachment_site" pos="0 0.1 0" quat="-1 1 0 0"/>
<!-- Gripper attached to wrist -->
<body name="gripper_base_mount" pos="0 0.1 0" quat="-1 1 0 0" childclass="gripper">
<body name="gripper_base_mount_inner" pos="0 0 0.007">
<geom class="visual_g" mesh="base_mount" material="black"/>
<geom class="collision_g" mesh="base_mount"/>
<body name="gripper_base" pos="0 0 0.0038" quat="1 0 0 -1">
<inertial mass="0.777441" pos="0 -2.70394e-05 0.0354675" quat="1 -0.00152849 0 0"
diaginertia="0.000260285 0.000225381 0.000152708"/>
<geom class="visual_g" mesh="base_g" material="black"/>
<geom class="collision_g" mesh="base_g"/>
<site name="pinch" pos="0 0 0.145" type="sphere" group="5" rgba="0.9 0.9 0.9 1" size="0.005"/>
<!-- End-effector site for IK -->
<site name="ee_site" pos="0 0 0.16" type="sphere" size="0.01" rgba="1 0 0 0.5"/>
<!-- Right-hand side 4-bar linkage -->
<body name="right_driver" pos="0 0.0306011 0.054904">
<inertial mass="0.00899563" pos="2.96931e-12 0.0177547 0.00107314" quat="0.681301 0.732003 0 0"
diaginertia="1.72352e-06 1.60906e-06 3.22006e-07"/>
<joint name="right_driver_joint" class="driver_j"/>
<geom class="visual_g" mesh="driver" material="gray"/>
<geom class="collision_g" mesh="driver"/>
<body name="right_coupler" pos="0 0.0315 -0.0041">
<inertial mass="0.0140974" pos="0 0.00301209 0.0232175" quat="0.705636 -0.0455904 0.0455904 0.705636"
diaginertia="4.16206e-06 3.52216e-06 8.88131e-07"/>
<joint name="right_coupler_joint" class="coupler_j"/>
<geom class="visual_g" mesh="coupler" material="black"/>
<geom class="collision_g" mesh="coupler"/>
</body>
</body>
<body name="right_spring_link" pos="0 0.0132 0.0609">
<inertial mass="0.0221642" pos="-8.65005e-09 0.0181624 0.0212658" quat="0.663403 -0.244737 0.244737 0.663403"
diaginertia="8.96853e-06 6.71733e-06 2.63931e-06"/>
<joint name="right_spring_link_joint" class="spring_link_j"/>
<geom class="visual_g" mesh="spring_link" material="black"/>
<geom class="collision_g" mesh="spring_link"/>
<body name="right_follower" pos="0 0.055 0.0375">
<inertial mass="0.0125222" pos="0 -0.011046 0.0124786" quat="1 0.1664 0 0"
diaginertia="2.67415e-06 2.4559e-06 6.02031e-07"/>
<joint name="right_follower_joint" class="follower_j"/>
<geom class="visual_g" mesh="follower" material="black"/>
<geom class="collision_g" mesh="follower"/>
<body name="right_pad" pos="0 -0.0189 0.01352">
<geom class="pad_box1" name="right_pad1"/>
<geom class="pad_box2" name="right_pad2"/>
<inertial mass="0.0035" pos="0 -0.0025 0.0185" quat="0.707107 0 0 0.707107"
diaginertia="4.73958e-07 3.64583e-07 1.23958e-07"/>
<geom class="visual_g" mesh="pad"/>
<body name="right_silicone_pad">
<geom class="visual_g" mesh="silicone_pad" material="black"/>
</body>
</body>
</body>
</body>
<!-- Left-hand side 4-bar linkage -->
<body name="left_driver" pos="0 -0.0306011 0.054904" quat="0 0 0 1">
<inertial mass="0.00899563" pos="0 0.0177547 0.00107314" quat="0.681301 0.732003 0 0"
diaginertia="1.72352e-06 1.60906e-06 3.22006e-07"/>
<joint name="left_driver_joint" class="driver_j"/>
<geom class="visual_g" mesh="driver" material="gray"/>
<geom class="collision_g" mesh="driver"/>
<body name="left_coupler" pos="0 0.0315 -0.0041">
<inertial mass="0.0140974" pos="0 0.00301209 0.0232175" quat="0.705636 -0.0455904 0.0455904 0.705636"
diaginertia="4.16206e-06 3.52216e-06 8.88131e-07"/>
<joint name="left_coupler_joint" class="coupler_j"/>
<geom class="visual_g" mesh="coupler" material="black"/>
<geom class="collision_g" mesh="coupler"/>
</body>
</body>
<body name="left_spring_link" pos="0 -0.0132 0.0609" quat="0 0 0 1">
<inertial mass="0.0221642" pos="-8.65005e-09 0.0181624 0.0212658" quat="0.663403 -0.244737 0.244737 0.663403"
diaginertia="8.96853e-06 6.71733e-06 2.63931e-06"/>
<joint name="left_spring_link_joint" class="spring_link_j"/>
<geom class="visual_g" mesh="spring_link" material="black"/>
<geom class="collision_g" mesh="spring_link"/>
<body name="left_follower" pos="0 0.055 0.0375">
<inertial mass="0.0125222" pos="0 -0.011046 0.0124786" quat="1 0.1664 0 0"
diaginertia="2.67415e-06 2.4559e-06 6.02031e-07"/>
<joint name="left_follower_joint" class="follower_j"/>
<geom class="visual_g" mesh="follower" material="black"/>
<geom class="collision_g" mesh="follower"/>
<body name="left_pad" pos="0 -0.0189 0.01352">
<geom class="pad_box1" name="left_pad1"/>
<geom class="pad_box2" name="left_pad2"/>
<inertial mass="0.0035" pos="0 -0.0025 0.0185" quat="1 0 0 1"
diaginertia="4.73958e-07 3.64583e-07 1.23958e-07"/>
<geom class="visual_g" mesh="pad"/>
<body name="left_silicone_pad">
<geom class="visual_g" mesh="silicone_pad" material="black"/>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
<!-- Optional: object to manipulate - Wandelbots lavender accent -->
<body name="box" pos="0.5 0.2 0.45">
<freejoint name="box_joint"/>
<geom name="box_geom" type="box" size="0.025 0.025 0.025" rgba="0.74 0.75 0.93 1" mass="0.1"/>
</body>
</worldbody>
<contact>
<exclude body1="gripper_base" body2="left_driver"/>
<exclude body1="gripper_base" body2="right_driver"/>
<exclude body1="gripper_base" body2="left_spring_link"/>
<exclude body1="gripper_base" body2="right_spring_link"/>
<exclude body1="right_coupler" body2="right_follower"/>
<exclude body1="left_coupler" body2="left_follower"/>
</contact>
<tendon>
<fixed name="split">
<joint joint="right_driver_joint" coef="0.5"/>
<joint joint="left_driver_joint" coef="0.5"/>
</fixed>
</tendon>
<equality>
<connect anchor="0 0 0" body1="right_follower" body2="right_coupler" solimp="0.95 0.99 0.001" solref="0.005 1"/>
<connect anchor="0 0 0" body1="left_follower" body2="left_coupler" solimp="0.95 0.99 0.001" solref="0.005 1"/>
<joint joint1="right_driver_joint" joint2="left_driver_joint" polycoef="0 1 0 0 0" solimp="0.95 0.99 0.001" solref="0.005 1"/>
</equality>
<actuator>
<!-- UR5e joint actuators -->
<general class="size3" name="shoulder_pan" joint="shoulder_pan_joint"/>
<general class="size3" name="shoulder_lift" joint="shoulder_lift_joint"/>
<general class="size3_limited" name="elbow" joint="elbow_joint"/>
<general class="size1" name="wrist_1" joint="wrist_1_joint"/>
<general class="size1" name="wrist_2" joint="wrist_2_joint"/>
<general class="size1" name="wrist_3" joint="wrist_3_joint"/>
<!-- Gripper actuator -->
<general name="gripper" tendon="split" forcerange="-5 5" ctrlrange="0 255" gainprm="0.3137255 0 0" biasprm="0 -100 -10"/>
</actuator>
<keyframe>
<!-- UR5e home pose updated to stable settled position with gripper open (0=open) -->
<key name="home" qpos="-3.22 -1.14 1.93 -2.36 -1.57 -1.72 0 0 0 0 0 0 0 0 0.5 0.2 0.45 1 0 0 0"
ctrl="-3.22 -1.14 1.93 -2.36 -1.57 -1.72 0"/>
</keyframe>
</mujoco>