69 lines
5 KiB
XML
69 lines
5 KiB
XML
<mujoco model="ur">
|
|
<compiler angle="radian" meshdir="meshes/"/>
|
|
<default/>
|
|
<asset>
|
|
<texture type="skybox" builtin="gradient" rgb1="0.9 0.9 0.9" rgb2="0.5 0.5 0.5" width="512" height="512"/>
|
|
<texture name="texplane" type="2d" builtin="checker" rgb1=".25 .25 .25" rgb2=".3 .3 .3" width="512" height="512" mark="cross" markrgb=".8 .8 .8"/>
|
|
<material name="matplane" reflectance="0.2" texture="texplane" texrepeat="1 1" texuniform="true"/>
|
|
<mesh name="base" file="base.stl"/>
|
|
<mesh name="shoulder" file="shoulder.stl"/>
|
|
<mesh name="upperarm" file="upperarm.stl"/>
|
|
<mesh name="forearm" file="forearm.stl"/>
|
|
<mesh name="wrist1" file="wrist1.stl"/>
|
|
<mesh name="wrist2" file="wrist2.stl"/>
|
|
<mesh name="wrist3" file="wrist3.stl"/>
|
|
</asset>
|
|
<worldbody>
|
|
<light directional="true" diffuse=".8 .8 .8" specular=".2 .2 .2" pos="0 0 5" dir="0 0 -1" castshadow="false"/>
|
|
<geom name="floor" pos="0 0 -0.0" size="0 0 1" type="plane" material="matplane"/>
|
|
<geom quat="-1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" mesh="base"/>
|
|
<geom quat="-1 0 0 0" type="mesh" mesh="base"/>
|
|
<body name="shoulder_link" pos="0 0 0.1625" quat="0 0 0 1" >
|
|
<inertial pos="0 0 0" mass="3.7" diaginertia="0.0102675 0.0102675 0.00666"/>
|
|
<joint name="shoulder_pan_joint" pos="0 0 0" axis="0 0 1" limited="true" range="-6.28319 6.28319"/>
|
|
<geom quat="0 0 0 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" mesh="shoulder"/>
|
|
<geom quat="0 0 0 1" type="mesh" mesh="shoulder"/>
|
|
<body name="upper_arm_link" pos="0 0 0" quat="0.5 0.5 0.5 -0.5" >
|
|
<inertial pos="-0.2125 0 0.138" quat="0.707107 0 0.707107 0" mass="8.393" diaginertia="0.133886 0.133886 0.0151074"/>
|
|
<joint name="shoulder_lift_joint" pos="0 0 0" axis="0 0 1" limited="true" range="-1.5708 1.5708"/>
|
|
<geom pos="0 0 0.138" quat="0.5 0.5 -0.5 -0.5" type="mesh" contype="0" conaffinity="0" group="1" density="0" mesh="upperarm"/>
|
|
<geom pos="0 0 0.138" quat="0.5 0.5 -0.5 -0.5" type="mesh" mesh="upperarm"/>
|
|
<body name="forearm_link" pos="-0.425 0 0" >
|
|
<inertial pos="-0.1961 0 0.007" quat="0.707107 0 0.707107 0" mass="2.275" diaginertia="0.0312094 0.0312094 0.004095"/>
|
|
<joint name="elbow_joint" pos="0 0 0" axis="0 0 1" limited="true" range="-2.75762 2.75762"/>
|
|
<geom pos="0 0 0.007" quat="0.5 0.5 -0.5 -0.5" type="mesh" contype="0" conaffinity="0" group="1" density="0" mesh="forearm"/>
|
|
<geom pos="0 0 0.007" quat="0.5 0.5 -0.5 -0.5" type="mesh" mesh="forearm"/>
|
|
<body name="wrist_1_link" pos="-0.3922 0 0.1333" quat="0.707107 0 0 -0.707107" >
|
|
<inertial pos="0 0 0" mass="1.219" diaginertia="0.0025599 0.0025599 0.0021942"/>
|
|
<joint name="wrist_1_joint" pos="0 0 0" axis="0 0 1" limited="true" range="-2.26893 2.26893"/>
|
|
<geom pos="0 0 -0.127" quat="0.707107 0.707107 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" mesh="wrist1"/>
|
|
<geom pos="0 0 -0.127" quat="0.707107 0.707107 0 0" type="mesh" mesh="wrist1"/>
|
|
<body name="wrist_2_link" pos="0 -0.0997 -2.04488e-11" quat="0.707107 0.707107 0 0" >
|
|
<inertial pos="0 0 0" mass="1.219" diaginertia="0.0025599 0.0025599 0.0021942"/>
|
|
<joint name="wrist_2_joint" pos="0 0 0" axis="0 0 1" limited="true" range="-2.53073 2.53073"/>
|
|
<geom pos="0 0 -0.0997" type="mesh" contype="0" conaffinity="0" group="1" density="0" mesh="wrist2"/>
|
|
<geom pos="0 0 -0.0997" type="mesh" mesh="wrist2"/>
|
|
<body name="wrist_3_link" pos="0 0.0996 -2.04283e-11" quat="0.707107 -0.707107 0 0" >
|
|
<inertial pos="0 -0.0173671 0.00936815" quat="0.683945 0.179497 -0.179497 0.683945" mass="0.2879" diaginertia="0.000833069 0.000825338 0.000124386"/>
|
|
<joint name="wrist_3_joint" pos="0 0 0" axis="0 0 1" limited="true" range="-6.28319 6.28319"/>
|
|
<geom pos="0 0 -0.0989" quat="0.707107 0.707107 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" mesh="wrist3"/>
|
|
<geom pos="0 0 -0.0989" quat="0.707107 0.707107 0 0" type="mesh" mesh="wrist3"/>
|
|
<geom size="0.005 0.005 0.005" pos="0 -0.05 0.07" quat="0.500398 0.5 -0.5 0.499602" type="box" contype="0" conaffinity="0" group="1" density="0" rgba="0 0 0 1"/>
|
|
<geom size="0.005 0.005 0.005" pos="0 -0.05 0.07" quat="0.500398 0.5 -0.5 0.499602" type="box" rgba="0 0 0 1"/>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</worldbody>
|
|
|
|
<actuator>
|
|
<motor name="shoulder_pan_joint" gear="1" joint="shoulder_pan_joint"/>
|
|
<motor name="shoulder_lift_joint" gear="1" joint="shoulder_lift_joint"/>
|
|
<motor name="elbow_joint" gear="1" joint="elbow_joint"/>
|
|
<motor name="wrist_1_joint" gear="1" joint="wrist_1_joint"/>
|
|
<motor name="wrist_2_joint" gear="1" joint="wrist_2_joint"/>
|
|
<motor name="wrist_3_joint" gear="1" joint="wrist_3_joint"/>
|
|
</actuator>
|
|
</mujoco>
|