137 lines
6.5 KiB
XML
137 lines
6.5 KiB
XML
|
<mujoco model="ur5e">
|
||
|
<compiler angle="radian" meshdir="assets" autolimits="true"/>
|
||
|
|
||
|
<option integrator="implicitfast"/>
|
||
|
|
||
|
<default>
|
||
|
<default class="ur5e">
|
||
|
<material specular="0.5" shininess="0.25"/>
|
||
|
<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>
|
||
|
|
||
|
<asset>
|
||
|
<material class="ur5e" name="black" rgba="0.033 0.033 0.033 1"/>
|
||
|
<material class="ur5e" name="jointgray" rgba="0.278 0.278 0.278 1"/>
|
||
|
<material class="ur5e" name="linkgray" rgba="0.82 0.82 0.82 1"/>
|
||
|
<material class="ur5e" name="urblue" rgba="0.49 0.678 0.8 1"/>
|
||
|
|
||
|
<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"/>
|
||
|
</asset>
|
||
|
|
||
|
<worldbody>
|
||
|
<light name="spotlight" mode="targetbodycom" target="wrist_2_link" pos="0 -1 2"/>
|
||
|
<body name="base" 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"/>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</worldbody>
|
||
|
|
||
|
<actuator>
|
||
|
<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"/>
|
||
|
</actuator>
|
||
|
|
||
|
<keyframe>
|
||
|
<key name="home" qpos="-1.5708 -1.5708 1.5708 -1.5708 -1.5708 0" ctrl="-1.5708 -1.5708 1.5708 -1.5708 -1.5708 0"/>
|
||
|
</keyframe>
|
||
|
</mujoco>
|