95 lines
8.3 KiB
XML
95 lines
8.3 KiB
XML
<mujocoinclue>
|
|
<body name="wam/base_link_right" pos="2.5 0 2" quat="0 0 1 0" childclass="wam" >
|
|
<inertial pos="0 0 0" mass="1" diaginertia="0.1 0.1 0.1"/>
|
|
<geom name="base_link_fine" class="viz" mesh="base_link_fine" rgba="0.5 0.5 0.5 0"/>
|
|
<geom name="base_link_convex" class="col" mesh="base_link_convex" rgba="0.5 0.5 0.5 1"/>
|
|
<body name="wam/shoulder_yaw_link_right" pos="0 0 0.346">
|
|
<inertial pos="-0.00443422 -0.00066489 -0.128904" quat="0.69566 0.716713 -0.0354863 0.0334839" mass="5"
|
|
diaginertia="0.135089 0.113095 0.0904426"/>
|
|
<joint name="wam/base_yaw_joint_right" range="-2.6 2.6" damping="1.98"/>
|
|
<geom name="shoulder_link_fine" class="viz" mesh="shoulder_link_fine" rgba="1 1 1 0"/>
|
|
<geom name="shoulder_link_convex_decomposition_p1" class="col"
|
|
mesh="shoulder_link_convex_decomposition_p1"/>
|
|
<geom name="shoulder_link_convex_decomposition_p2" class="col"
|
|
mesh="shoulder_link_convex_decomposition_p2"/>
|
|
<geom name="shoulder_link_convex_decomposition_p3" class="col"
|
|
mesh="shoulder_link_convex_decomposition_p3"/>
|
|
<body name="wam/shoulder_pitch_link_right" pos="0 0 0" quat="0.707107 -0.707107 0 0">
|
|
<inertial pos="-0.00236981 -0.0154211 0.0310561" quat="0.961794 0.273112 -0.0169316 0.00866592"
|
|
mass="3.87494" diaginertia="0.0214195 0.0167127 0.0126452"/> <!--seems off-->
|
|
<joint name="wam/shoulder_pitch_joint_right" range="-2 2" damping="0.55"/>
|
|
<geom name="shoulder_pitch_link_fine" class="viz" mesh="shoulder_pitch_link_fine" rgba="1 1 1 0"/>
|
|
<geom name="shoulder_pitch_link_convex" class="col" mesh="shoulder_pitch_link_convex"/>
|
|
<body name="wam/upper_arm_link_right" pos="0 0 0" quat="0.707107 0.707107 0 0">
|
|
<inertial pos="0.00683259 3.309e-005 0.392492" quat="0.647136 0.0170822 0.0143038 0.762049"
|
|
mass="2.20228" diaginertia="0.0592718 0.0592207 0.00313419"/>
|
|
<joint name="wam/shoulder_yaw_joint_right" range="-2.8 2.8" damping="1.65"/>
|
|
<geom name="upper_arm_link_fine" class="viz" mesh="upper_arm_link_fine" rgba="1 1 1 0"/>
|
|
<geom name="upper_arm_link_convex_decomposition_p1" class="col"
|
|
mesh="upper_arm_link_convex_decomposition_p1" rgba="0.094 0.48 0.804 1"/>
|
|
<geom name="upper_arm_link_convex_decomposition_p2" class="col"
|
|
mesh="upper_arm_link_convex_decomposition_p2" rgba="0.094 0.48 0.804 1"/>
|
|
<body name="wam/forearm_link_right" pos="0.045 0 0.55" quat="0.707107 -0.707107 0 0">
|
|
<inertial pos="-0.0400149 -0.142717 -0.00022942"
|
|
quat="0.704281 0.706326 0.0180333 0.0690353" mass="0.500168"
|
|
diaginertia="0.0151047 0.0148285 0.00275805"/>
|
|
<joint name="wam/elbow_pitch_joint_right" range="-0.9 3.1" damping="0.88"/>
|
|
<geom name="elbow_link_fine" class="viz" mesh="elbow_link_fine" rgba="1 1 1 0"/>
|
|
<geom name="elbow_link_convex" class="col" mesh="elbow_link_convex"/>
|
|
<geom name="forearm_link_fine" class="viz" mesh="forearm_link_fine" pos="-.045 -0.0730 0"
|
|
euler="1.57 0 0" rgba="1 1 1 0"/>
|
|
<geom name="forearm_link_convex_decomposition_p1" class="col"
|
|
mesh="forearm_link_convex_decomposition_p1" pos="-0.045 -0.0730 0"
|
|
euler="1.57 0 0" rgba="0.094 0.48 0.804 1"/>
|
|
<geom name="forearm_link_convex_decomposition_p2" class="col"
|
|
mesh="forearm_link_convex_decomposition_p2" pos="-.045 -0.0730 0"
|
|
euler="1.57 0 0" rgba="0.094 0.48 0.804 1"/>
|
|
<body name="wam/wrist_yaw_link_right" pos="-0.045 -0.3 0" quat="0.707107 0.707107 0 0">
|
|
<inertial pos="8.921e-005 0.00435824 -0.00511217"
|
|
quat="0.630602 0.776093 0.00401969 -0.002372" mass="1.05376"
|
|
diaginertia="0.000555168 0.00046317 0.000234072"/> <!--this is an approximation-->
|
|
<joint name="wam/wrist_yaw_joint_right" range="-4.8 1.3" damping="0.55"/>
|
|
<geom name="wrist_yaw_link_fine" class="viz" mesh="wrist_yaw_link_fine" rgba="1 1 1 0"/>
|
|
<geom name="wrist_yaw_link_convex_decomposition_p1" class="col"
|
|
mesh="wrist_yaw_link_convex_decomposition_p1"/>
|
|
<geom name="wrist_yaw_link_convex_decomposition_p2" class="col"
|
|
mesh="wrist_yaw_link_convex_decomposition_p2"/>
|
|
<body name="wam/wrist_pitch_link_right" pos="0 0 0" quat="0.707107 -0.707107 0 0">
|
|
<inertial pos="-0.00012262 -0.0246834 -0.0170319"
|
|
quat="0.630602 0.776093 0.00401969 -0.002372" mass="0.517974"
|
|
diaginertia="0.000555168 0.00046317 0.000234072"/>
|
|
<joint name="wam/wrist_pitch_joint_right" range="-1.6 1.6" damping="0.11"/>
|
|
<geom name="wrist_pitch_link_fine" class="viz" mesh="wrist_pitch_link_fine"
|
|
rgba="1 1 1 0"/>
|
|
<geom name="wrist_pitch_link_convex_decomposition_p1" rgba="1 0.5 0.313 1"
|
|
class="col" mesh="wrist_pitch_link_convex_decomposition_p1"/>
|
|
<geom name="wrist_pitch_link_convex_decomposition_p2" rgba="1 0.5 0.313 1"
|
|
class="col" mesh="wrist_pitch_link_convex_decomposition_p2"/>
|
|
<geom name="wrist_pitch_link_convex_decomposition_p3" rgba="1 0.5 0.313 1"
|
|
class="col" mesh="wrist_pitch_link_convex_decomposition_p3"/>
|
|
<body name="wam/wrist_palm_link_right" pos="0 0 0" quat="0.707107 0.707107 0 0">
|
|
<inertial pos="0 0 0.055" quat="0.707107 0 0 0.707107" mass="0.0828613"
|
|
diaginertia="0.00020683 0.00010859 0.00010851"/>
|
|
<joint name="wam/palm_yaw_joint_right" range="-2.2 2.2" damping="0.11"/>
|
|
<geom name="wrist_palm_link_fine" class="viz" mesh="wrist_palm_link_fine"
|
|
rgba="1 1 1 0"/>
|
|
<geom name="wrist_palm_link_convex" class="col" mesh="wrist_palm_link_convex"/>
|
|
<!-- EE=wam/paddle, configure name to the end effector name-->
|
|
<body name="EE" pos="0 0 0.26" childclass="contact_geom">
|
|
<geom name="bat" type="cylinder" size="0.075 0.005" rgba="1 0 0 1"
|
|
quat="0.71 0 0.71 0"/>
|
|
<geom name="wam/paddle_handle" type="box" size="0.005 0.01 0.05" pos="0 0 -0.08"
|
|
rgba="1 1 1 1"/>
|
|
<!-- Extract information for sampling goals.-->
|
|
<site name="wam/paddle_center" pos="0 0 0" rgba="1 1 1 1" size="0.00001"/>
|
|
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</mujocoinclue> |