| <?xml version="1.0" encoding="UTF-8"?> |
| <robot name="sawyer_v2"> |
| <joint name="controller_box_fixed" type="fixed"> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <parent link="base"/> |
| <child link="controller_box"/> |
| </joint> |
| <joint name="display_joint" type="fixed"> |
| <origin xyz="0.03 0. 0.1050001" rpy="1.5707963 0. 1.5707964"/> |
| <parent link="head"/> |
| <child link="screen"/> |
| </joint> |
| <joint name="head_head_camera" type="fixed"> |
| <origin xyz="0.0228027 0. 0.2165721" rpy="-1.5707963 -0.5585038 3.1415925"/> |
| <parent link="head"/> |
| <child link="sawyer_head_camera"/> |
| </joint> |
| <joint name="head_pan" type="revolute"> |
| <origin xyz="0. 0. 0.2965" rpy="0. 0. 0."/> |
| <parent link="right_l0"/> |
| <child link="head"/> |
| <axis xyz="0. 0. 1."/> |
| <limit lower="-5.0951992" upper="0.9064" effort="8." velocity="1.8"/> |
| </joint> |
| <joint name="pedestal_feet_fixed" type="fixed"> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <parent link="base"/> |
| <child link="pedestal_feet"/> |
| </joint> |
| <joint name="pedestal_fixed" type="fixed"> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <parent link="base"/> |
| <child link="pedestal"/> |
| </joint> |
| <joint name="right_arm_mount" type="fixed"> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <parent link="base"/> |
| <child link="right_arm_base_link"/> |
| </joint> |
| <joint name="right_connector_plate_base_joint" type="fixed"> |
| <origin xyz="0. 0. 0.0018" rpy="0. 0. 0."/> |
| <parent link="right_gripper_base"/> |
| <child link="right_connector_plate_base"/> |
| </joint> |
| <joint name="right_connector_plate_mount_joint" type="fixed"> |
| <origin xyz="0. -0. 0.0176001" rpy="0. 0. 0."/> |
| <parent link="right_connector_plate_base"/> |
| <child link="right_connector_plate_mount"/> |
| </joint> |
| <joint name="right_electric_gripper_base_joint" type="fixed"> |
| <origin xyz="0. -0. -0.0000001" rpy="0. 0. 0."/> |
| <parent link="right_connector_plate_mount"/> |
| <child link="right_electric_gripper_base"/> |
| </joint> |
| <joint name="right_gripper_base_joint" type="fixed"> |
| <origin xyz="0. 0. -0.005" rpy="-0.0000001 0. -0. "/> |
| <parent link="sawyer_right_hand"/> |
| <child link="right_gripper_base"/> |
| </joint> |
| <joint name="right_gripper_l_finger_joint" type="prismatic"> |
| <origin xyz="0.003 -0.0015 0.04552" rpy="-0. 0.0000001 -0.0000002"/> |
| <parent link="right_electric_gripper_base"/> |
| <child link="right_gripper_l_finger"/> |
| <axis xyz="0. 1. 0."/> |
| <limit lower="0." upper="0.020833" effort="20." velocity="5."/> |
| </joint> |
| <joint name="right_gripper_l_finger_tip_joint" type="fixed"> |
| <origin xyz="-0. 0.01725 0.075 " rpy="0.0000001 0. -0.0000001"/> |
| <parent link="right_gripper_l_finger"/> |
| <child link="right_gripper_l_finger_tip"/> |
| </joint> |
| <joint name="right_gripper_r_finger_joint" type="prismatic"> |
| <origin xyz="0.003 0.0015 0.04552" rpy="-0. 0.0000001 -0.0000002"/> |
| <parent link="right_electric_gripper_base"/> |
| <child link="right_gripper_r_finger"/> |
| <axis xyz="0. 1. 0."/> |
| <limit lower="-0.020833" upper="0." effort="340282346638528859811704183484516925440." velocity="5."/> |
| </joint> |
| <joint name="right_gripper_r_finger_tip_joint" type="fixed"> |
| <origin xyz="-0. -0.01725 0.0750001" rpy="0. -0.0000001 0. "/> |
| <parent link="right_gripper_r_finger"/> |
| <child link="right_gripper_r_finger_tip"/> |
| </joint> |
| <joint name="right_gripper_tip_joint" type="fixed"> |
| <origin xyz="0. 0. 0.14062" rpy="0. 0. 0."/> |
| <parent link="right_gripper_base"/> |
| <child link="right_gripper_tip"/> |
| </joint> |
| <joint name="right_j0" type="revolute"> |
| <origin xyz="0. 0. 0.08" rpy="0. 0. 0."/> |
| <parent link="right_arm_base_link"/> |
| <child link="right_l0"/> |
| <axis xyz="0. 0. 1."/> |
| <limit lower="-3.0502998" upper="3.0502998" effort="80." velocity="1.74"/> |
| </joint> |
| <joint name="right_j1" type="revolute"> |
| <origin xyz="0.081 0.05 0.237" rpy="-1.5707964 1.5707963 0. "/> |
| <parent link="right_l0"/> |
| <child link="right_l1"/> |
| <axis xyz="0. 0. 1."/> |
| <limit lower="-3.8094999" upper="2.2736" effort="80." velocity="1.3279999"/> |
| </joint> |
| <joint name="right_j1_2" type="fixed"> |
| <origin xyz="-0. 0. 0." rpy="0. 0. -0.0000167"/> |
| <parent link="right_l1"/> |
| <child link="right_l1_2"/> |
| </joint> |
| <joint name="right_j2" type="revolute"> |
| <origin xyz="-0.0000024 -0.14 0.1425 " rpy="1.5707964 0. -0.0000167"/> |
| <parent link="right_l1"/> |
| <child link="right_l2"/> |
| <axis xyz="0. 0. 1."/> |
| <limit lower="-3.0425998" upper="3.0425998" effort="40." velocity="1.957"/> |
| </joint> |
| <joint name="right_j2_2" type="fixed"> |
| <origin xyz="-0. 0.0000001 0.0000001" rpy="0. 0.0000001 -0.0000032"/> |
| <parent link="right_l2"/> |
| <child link="right_l2_2"/> |
| </joint> |
| <joint name="right_j3" type="revolute"> |
| <origin xyz="-0.0000001 -0.042 0.2600001" rpy="-1.5707963 0.0000001 -0.0000032"/> |
| <parent link="right_l2"/> |
| <child link="right_l3"/> |
| <axis xyz="0. 0. 1."/> |
| <limit lower="-3.0438999" upper="3.0438999" effort="40." velocity="1.957"/> |
| </joint> |
| <joint name="right_j4" type="revolute"> |
| <origin xyz="-0.0000002 -0.1250001 -0.1265 " rpy="1.5707961 0.0000002 -0.0000014"/> |
| <parent link="right_l3"/> |
| <child link="right_l4"/> |
| <axis xyz="0. 0. 1."/> |
| <limit lower="-2.9760996" upper="2.9760996" effort="9." velocity="3.4849998"/> |
| </joint> |
| <joint name="right_j4_2" type="fixed"> |
| <origin xyz="-0. -0.0000001 0. " rpy="0.0000001 -0.0000001 -0.0000002"/> |
| <parent link="right_l4"/> |
| <child link="right_l4_2"/> |
| </joint> |
| <joint name="right_j5" type="revolute"> |
| <origin xyz="-0. 0.0309999 0.2750001" rpy="-1.5707963 -0.0000001 -0.0000002"/> |
| <parent link="right_l4"/> |
| <child link="right_l5"/> |
| <axis xyz="0. 0. 1."/> |
| <limit lower="-2.9760996" upper="2.9760996" effort="9." velocity="3.4849998"/> |
| </joint> |
| <joint name="right_j6" type="revolute"> |
| <origin xyz="-0. -0.11 0.1053" rpy="-1.5707963 -0.17453 -3.1415854"/> |
| <parent link="right_l5"/> |
| <child link="right_l6"/> |
| <axis xyz="0. 0. 1."/> |
| <limit lower="-4.7123991" upper="4.7123991" effort="9." velocity="4.5450003"/> |
| </joint> |
| <joint name="right_l0_right_torso_itb" type="fixed"> |
| <origin xyz="-0.055 -0. 0.22 " rpy="0. -1.5707963 0. "/> |
| <parent link="right_l0"/> |
| <child link="sawyer_right_torso_itb"/> |
| </joint> |
| <joint name="right_l4_right_arm_itb" type="fixed"> |
| <origin xyz="-0.055 -0.0000001 0.075 " rpy="-0.0000002 -1.5707963 0. "/> |
| <parent link="right_l4"/> |
| <child link="sawyer_right_arm_itb"/> |
| </joint> |
| <joint name="right_l5_right_hand_camera" type="fixed"> |
| <origin xyz="0.039552 -0.033 0.0695 " rpy="-3.1415925 0. -3.1415925"/> |
| <parent link="right_l5"/> |
| <child link="sawyer_right_hand_camera"/> |
| </joint> |
| <joint name="right_l5_right_wrist" type="fixed"> |
| <origin xyz="-0. -0. 0.10541" rpy="1.5707963 0. 1.5707964"/> |
| <parent link="right_l5"/> |
| <child link="sawyer_right_wrist"/> |
| </joint> |
| <joint name="right_l6_right_hand" type="fixed"> |
| <origin xyz="0. -0. 0.0245001" rpy="0.0000001 -0.0000001 1.570796 "/> |
| <parent link="right_l6"/> |
| <child link="sawyer_right_hand"/> |
| </joint> |
| <joint name="sawyer_root_joint" type="fixed"> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <parent link="sawyer"/> |
| <child link="sawyer_sawyer"/> |
| </joint> |
| <joint name="sawyer_sawyer_root_joint" type="fixed"> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <parent link="sawyer_sawyer"/> |
| <child link="base"/> |
| </joint> |
| <joint name="torso_t0" type="fixed"> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <parent link="base"/> |
| <child link="torso"/> |
| </joint> |
| <link name="base"> |
| <inertial> |
| <origin xyz="-inf -inf -inf" rpy="0. 0. 0."/> |
| <mass value="0.000001"/> |
| <inertia ixx="0.00001" ixy="0." ixz="0." iyy="0.00001" iyz="0." izz="0.00001"/> |
| </inertial> |
| </link> |
| <link name="controller_box"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="0.000001"/> |
| <inertia ixx="0.001" ixy="0." ixz="0." iyy="0.001" iyz="0." izz="0.001"/> |
| </inertial> |
| <visual> |
| <origin xyz="-0.325 0. -0.38 " rpy="0. 0. 0."/> |
| <geometry> |
| <box size="0.22 0.4 0.53"/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="-0.325 0. -0.38 " rpy="0. 0. 0."/> |
| <geometry> |
| <box size="0.22 0.4 0.53"/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="head"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="1.5795"/> |
| <inertia ixx="0.001" ixy="0." ixz="0." iyy="0.001" iyz="0." izz="0.001"/> |
| </inertial> |
| <visual> |
| <origin xyz="0. 0. 0.0000001" rpy="0. -0. 0."/> |
| <geometry> |
| <mesh filename="meshes/head_visuals.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| </link> |
| <link name="pedestal"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="60.8639793"/> |
| <inertia ixx="0.001" ixy="0." ixz="0." iyy="0.001" iyz="0." izz="0.001"/> |
| </inertial> |
| <visual> |
| <origin xyz="0.26 0.345 -0.91488" rpy="1.5707964 0. -1.5707964"/> |
| <geometry> |
| <mesh filename="meshes/pedestal_visuals.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="-0.02 0. -0.29" rpy="0. 0. 0."/> |
| <geometry> |
| <cylinder radius="0.18" length="0.62"/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="pedestal_feet"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="0.000001"/> |
| <inertia ixx="0.001" ixy="0." ixz="0." iyy="0.001" iyz="0." izz="0.001"/> |
| </inertial> |
| <collision> |
| <origin xyz="-0.1225 0. -0.758 " rpy="0. 0. 0."/> |
| <geometry> |
| <box size="0.77 0.7 0.31"/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="right_arm_base_link"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="2.0687001"/> |
| <inertia ixx="0.001" ixy="0." ixz="0." iyy="0.001" iyz="0." izz="0.001"/> |
| </inertial> |
| <visual> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <geometry> |
| <mesh filename="meshes/right_arm_base_link_visuals.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="0. 0. 0.12" rpy="0. 0. 0."/> |
| <geometry> |
| <cylinder radius="0.08" length="0.24"/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="right_connector_plate_base"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="0.000001"/> |
| <inertia ixx="0.001" ixy="0." ixz="0." iyy="0.001" iyz="0." izz="0.001"/> |
| </inertial> |
| <visual> |
| <origin xyz="-0. 0. 0.0000002" rpy="0. 0. 0."/> |
| <geometry> |
| <mesh filename="meshes/right_connector_plate_base_visuals.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="0. -0. 0.0135001" rpy="0. 0. 0."/> |
| <geometry> |
| <cylinder radius="0.04" length="0.0302"/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="right_connector_plate_mount"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="0.000001"/> |
| <inertia ixx="0.00001" ixy="0." ixz="0." iyy="0.00001" iyz="0." izz="0.00001"/> |
| </inertial> |
| </link> |
| <link name="right_electric_gripper_base"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="0.000002"/> |
| <inertia ixx="0.001" ixy="0." ixz="0." iyy="0.001" iyz="0." izz="0.001"/> |
| </inertial> |
| <visual> |
| <origin xyz="-0. 0. 0." rpy="-0. 0.0000001 -0.0000002"/> |
| <geometry> |
| <mesh filename="meshes/right_electric_gripper_base_visuals.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="0.004 -0. 0.025" rpy="1.5707964 -0.0000002 3.1415925"/> |
| <geometry> |
| <cylinder radius="0.029" length="0.1"/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="right_gripper_base"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="0.47"/> |
| <inertia ixx="0.00001" ixy="0." ixz="0." iyy="0.00001" iyz="0." izz="0.00001"/> |
| </inertial> |
| </link> |
| <link name="right_gripper_l_finger"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="0.001"/> |
| <inertia ixx="0.001" ixy="0." ixz="0." iyy="0.001" iyz="0." izz="0.001"/> |
| </inertial> |
| <visual> |
| <origin xyz="0. -0. -0." rpy="-0.0000001 -0. 3.1415925"/> |
| <geometry> |
| <mesh filename="meshes/right_gripper_l_finger_visuals_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <visual> |
| <origin xyz="-0. 0.01725 0.04 " rpy="-0.0000001 -0. 3.1415925"/> |
| <geometry> |
| <box size="0.01 0.0135 0.075 "/> |
| </geometry> |
| </visual> |
| <visual> |
| <origin xyz="-0.005 -0.003 0.0083" rpy="-0.0000001 -0. 3.1415925"/> |
| <geometry> |
| <box size="0.01 0.05 0.017"/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="-0. 0.01725 0.04 " rpy="-0.0000001 -0. 3.1415925"/> |
| <geometry> |
| <box size="0.01 0.0135 0.075 "/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="right_gripper_l_finger_tip"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="0.001"/> |
| <inertia ixx="0.001" ixy="0." ixz="0." iyy="0.001" iyz="0." izz="0.001"/> |
| </inertial> |
| <visual> |
| <origin xyz="-0. -0. -0." rpy="-0.0000001 0.0000003 -3.1415923"/> |
| <geometry> |
| <mesh filename="meshes/right_gripper_l_finger_tip_visuals_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <visual> |
| <origin xyz="-0. -0.0045 -0.015 " rpy="-0.0000001 0.0000003 -3.1415923"/> |
| <geometry> |
| <box size="0.016 0.007 0.037"/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="-0. -0.0045 -0.015 " rpy="-0.0000001 0.0000003 -3.1415923"/> |
| <geometry> |
| <box size="0.016 0.007 0.037"/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="right_gripper_r_finger"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="0.001"/> |
| <inertia ixx="0.001" ixy="0." ixz="0." iyy="0.001" iyz="0." izz="0.001"/> |
| </inertial> |
| <visual> |
| <origin xyz="-0. -0. 0.0000001" rpy="0. -0.0000001 0. "/> |
| <geometry> |
| <mesh filename="meshes/right_gripper_r_finger_visuals_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <visual> |
| <origin xyz="-0. -0.01725 0.0400001" rpy="0. -0.0000001 0. "/> |
| <geometry> |
| <box size="0.01 0.0135 0.075 "/> |
| </geometry> |
| </visual> |
| <visual> |
| <origin xyz="0.005 0.003 0.0083001" rpy="0. -0.0000001 0. "/> |
| <geometry> |
| <box size="0.01 0.05 0.017"/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="-0. -0.01725 0.0400001" rpy="0. -0.0000001 0. "/> |
| <geometry> |
| <box size="0.01 0.0135 0.075 "/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="right_gripper_r_finger_tip"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="0.001"/> |
| <inertia ixx="0.001" ixy="0." ixz="0." iyy="0.001" iyz="0." izz="0.001"/> |
| </inertial> |
| <visual> |
| <origin xyz="0. -0. -0." rpy="0.0000003 0. 0.0000001"/> |
| <geometry> |
| <mesh filename="meshes/right_gripper_r_finger_tip_visuals_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <visual> |
| <origin xyz="0. 0.0045 -0.015 " rpy="0.0000003 0. 0.0000001"/> |
| <geometry> |
| <box size="0.016 0.007 0.037"/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="0. 0.0045 -0.015 " rpy="0.0000003 0. 0.0000001"/> |
| <geometry> |
| <box size="0.016 0.007 0.037"/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="right_gripper_tip"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="0.000002"/> |
| <inertia ixx="0.00001" ixy="0." ixz="0." iyy="0.00001" iyz="0." izz="0.00001"/> |
| </inertial> |
| </link> |
| <link name="right_l0"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="5.3213"/> |
| <inertia ixx="0.001" ixy="0." ixz="0." iyy="0.001" iyz="0." izz="0.001"/> |
| </inertial> |
| <visual> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <geometry> |
| <mesh filename="meshes/right_l0_visuals.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="0.08 0. 0.23" rpy="0. 0. 0."/> |
| <geometry> |
| <sphere radius="0.07"/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="right_l1"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="4.5050001"/> |
| <inertia ixx="0.001" ixy="0." ixz="0." iyy="0.001" iyz="0." izz="0.001"/> |
| </inertial> |
| <visual> |
| <origin xyz="-0. 0. 0." rpy="0. 0. -0.0000167"/> |
| <geometry> |
| <mesh filename="meshes/right_l1_visuals.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <visual> |
| <origin xyz="0.0058472 0.0333626 0.146406 " rpy="0. 0. -0.0000167"/> |
| <geometry> |
| <sphere radius="0.0444539"/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="-0. -0. 0.1225" rpy="0. 0. -0.0000167"/> |
| <geometry> |
| <sphere radius="0.07"/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="right_l1_2"> |
| <collision> |
| <origin xyz="0. 0. 0.035" rpy="0. 0. 0."/> |
| <geometry> |
| <cylinder radius="0.07" length="0.14"/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="right_l2"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="1.745"/> |
| <inertia ixx="0.001" ixy="0." ixz="0." iyy="0.001" iyz="0." izz="0.001"/> |
| </inertial> |
| <visual> |
| <origin xyz="-0. 0.0000001 0.0000001" rpy="0. 0.0000001 -0.0000032"/> |
| <geometry> |
| <mesh filename="meshes/right_l2_visuals.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="-0. 0.0000001 0.0800001" rpy="0. 0.0000001 -0.0000032"/> |
| <geometry> |
| <cylinder radius="0.06" length="0.34"/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="right_l2_2"> |
| <collision> |
| <origin xyz="0. 0. 0.26" rpy="0. 0. 0."/> |
| <geometry> |
| <sphere radius="0.06"/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="right_l3"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="2.5097001"/> |
| <inertia ixx="0.001" ixy="0." ixz="0." iyy="0.001" iyz="0." izz="0.001"/> |
| </inertial> |
| <visual> |
| <origin xyz="-0. -0.0000001 0. " rpy="-0.0000001 0.0000002 -0.0000014"/> |
| <geometry> |
| <mesh filename="meshes/right_l3_visuals.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="-0.0000001 -0.0100001 -0.12 " rpy="-0.0000001 0.0000002 -0.0000014"/> |
| <geometry> |
| <sphere radius="0.06"/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="right_l4"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="1.1136"/> |
| <inertia ixx="0.001" ixy="0." ixz="0." iyy="0.001" iyz="0." izz="0.001"/> |
| </inertial> |
| <visual> |
| <origin xyz="-0. -0.0000001 0. " rpy="0.0000001 -0.0000001 -0.0000002"/> |
| <geometry> |
| <mesh filename="meshes/right_l4_visuals.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="-0. -0.0000001 0.11 " rpy="0.0000001 -0.0000001 -0.0000002"/> |
| <geometry> |
| <cylinder radius="0.045" length="0.3"/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="right_l4_2"> |
| <collision> |
| <origin xyz="0. 0.01 0.26" rpy="0. 0. 0."/> |
| <geometry> |
| <sphere radius="0.06"/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="right_l5"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="1.5625"/> |
| <inertia ixx="0.001" ixy="0." ixz="0." iyy="0.001" iyz="0." izz="0.001"/> |
| </inertial> |
| <visual> |
| <origin xyz="0. -0. 0." rpy="-0. -0. -0."/> |
| <geometry> |
| <mesh filename="meshes/right_l5_visuals.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="-0. -0. 0.1" rpy="-0. -0. -0."/> |
| <geometry> |
| <sphere radius="0.06"/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="right_l6"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="0.3292"/> |
| <inertia ixx="0.001" ixy="0." ixz="0." iyy="0.001" iyz="0." izz="0.001"/> |
| </inertial> |
| <visual> |
| <origin xyz="0.0000001 0. 0.0000004" rpy="0.0000001 0.0000001 0.0000001"/> |
| <geometry> |
| <mesh filename="meshes/right_l6_visuals.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="0. 0.015 -0.0099999" rpy="0.0000001 0.0000001 0.0000001"/> |
| <geometry> |
| <cylinder radius="0.055" length="0.05"/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="sawyer"/> |
| <link name="sawyer_head_camera"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="0.000001"/> |
| <inertia ixx="0.00001" ixy="0." ixz="0." iyy="0.00001" iyz="0." izz="0.00001"/> |
| </inertial> |
| </link> |
| <link name="sawyer_right_arm_itb"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="0.0001"/> |
| <inertia ixx="0.00001" ixy="0." ixz="0." iyy="0.00001" iyz="0." izz="0.00001"/> |
| </inertial> |
| </link> |
| <link name="sawyer_right_hand"> |
| <visual> |
| <origin xyz="0. -0. 0.02" rpy="-0.0000001 0. -0. "/> |
| <geometry> |
| <cylinder radius="0.035" length="0.03"/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="0. -0. 0.02" rpy="-0.0000001 0. -0. "/> |
| <geometry> |
| <cylinder radius="0.035" length="0.03"/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="sawyer_right_hand_camera"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="0.000001"/> |
| <inertia ixx="0.00001" ixy="0." ixz="0." iyy="0.00001" iyz="0." izz="0.00001"/> |
| </inertial> |
| </link> |
| <link name="sawyer_right_torso_itb"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="0.0001"/> |
| <inertia ixx="0.00001" ixy="0." ixz="0." iyy="0.00001" iyz="0." izz="0.00001"/> |
| </inertial> |
| </link> |
| <link name="sawyer_right_wrist"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="0.000001"/> |
| <inertia ixx="0.00001" ixy="0." ixz="0." iyy="0.00001" iyz="0." izz="0.00001"/> |
| </inertial> |
| </link> |
| <link name="sawyer_sawyer"/> |
| <link name="screen"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="0.0001"/> |
| <inertia ixx="0.001" ixy="0." ixz="0." iyy="0.001" iyz="0." izz="0.001"/> |
| </inertial> |
| <visual> |
| <origin xyz="-0. -0. 0." rpy="0. -0. 0."/> |
| <geometry> |
| <box size="0.24 0.14 0.002"/> |
| </geometry> |
| </visual> |
| <visual> |
| <origin xyz="-0. -0. 0." rpy="0. -0. 0."/> |
| <geometry> |
| <sphere radius="0.001"/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="-0. -0. 0." rpy="0. -0. 0."/> |
| <geometry> |
| <sphere radius="0.001"/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="torso"> |
| <inertial> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <mass value="0.0001"/> |
| <inertia ixx="0.00001" ixy="0." ixz="0." iyy="0.00001" iyz="0." izz="0.00001"/> |
| </inertial> |
| <visual> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <geometry> |
| <box size="0.001 0.001 0.001"/> |
| </geometry> |
| </visual> |
| </link> |
| </robot> |
|
|