| <robot name="fetch"> |
| <link name="base_link"> |
| <inertial> |
| <origin rpy="0 0 0" xyz="-0.0036 0.0 0.0014" /> |
| <mass value="70.1294" /> |
| <inertia ixx="1.225" ixy="0.0099" ixz="0.0062" iyy="1.2853" iyz="-0.0034" izz="0.987" /> |
| </inertial> |
| <visual> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/base_link.obj" /> |
| </geometry> |
| </visual> |
| <collision> |
| <origin rpy="0 0 0" xyz="0 0 0.0" /> |
| <geometry> |
| <mesh filename="meshes/base_link_collision.STL" /> |
| </geometry> |
| </collision> |
|
|
| <contact> |
| <lateral_friction value="0.0"/> |
| <rolling_friction value="0.0"/> |
| <stiffness value="300000"/> |
| <damping value="30000"/> |
| </contact> |
| </link> |
|
|
| <link name="r_wheel_link"> |
| <inertial> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <mass value="4.3542" /> |
| <inertia ixx="0.0045" ixy="0" ixz="0" iyy="0.005" iyz="0" izz="0.0045" /> |
| </inertial> |
| <visual> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/r_wheel_link.obj" /> |
| </geometry> |
| </visual> |
| <collision> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <sphere radius="0.0613"/> |
| </geometry> |
| </collision> |
| <contact> |
| <lateral_friction value="1.0"/> |
| <rolling_friction value="0.0"/> |
| <stiffness value="300000"/> |
| <damping value="30000"/> |
| </contact> |
| </link> |
| <joint name="r_wheel_joint" type="continuous"> |
| <origin rpy="-6.123E-17 0 0" xyz="0.0012914 -0.18738 0.06" /> |
| <parent link="base_link" /> |
| <child link="r_wheel_link" /> |
| <axis xyz="0 1 0" /> |
| <limit effort="8.85" velocity="17.4" /></joint> |
| <link name="l_wheel_link"> |
| <inertial> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <mass value="4.3542" /> |
| <inertia ixx="0.0045" ixy="0" ixz="0" iyy="0.005" iyz="0" izz="0.0045" /> |
| </inertial> |
| <visual> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/l_wheel_link.obj" /> |
| </geometry> |
| </visual> |
| <collision> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <sphere radius="0.0613"/> |
| </geometry> |
| </collision> |
| <contact> |
| <lateral_friction value="1.0"/> |
| <rolling_friction value="0.0"/> |
| <stiffness value="300000"/> |
| <damping value="30000"/> |
| </contact> |
|
|
| </link> |
| <joint name="l_wheel_joint" type="continuous"> |
| <origin rpy="-6.123E-17 0 0" xyz="0.0012914 0.18738 0.06" /> |
| <parent link="base_link" /> |
| <child link="l_wheel_link" /> |
| <axis xyz="0 1 0" /> |
| <limit effort="8.85" velocity="17.4" /></joint> |
| <link name="torso_lift_link"> |
| <inertial> |
| <origin rpy="0 0 0" xyz="-0.0013 -0.0009 0.2935" /> |
| <mass value="10.7796" /> |
| <inertia ixx="0.3354" ixy="0.0" ixz="-0.0162" iyy="0.3354" iyz="-0.0006" izz="0.0954" /> |
| </inertial> |
| <visual> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/torso_lift_link.obj" /> |
| </geometry> |
| </visual> |
| <collision> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/torso_lift_link_collision.STL" /> |
| </geometry> |
| </collision> |
| </link> |
| <joint name="torso_lift_joint" type="prismatic"> |
| <origin rpy="-6.123E-17 0 0" xyz="-0.086875 0 0.37743" /> |
| <parent link="base_link" /> |
| <child link="torso_lift_link" /> |
| <axis xyz="0 0 1" /> |
| <limit effort="450.0" lower="0" upper="0.38615" velocity="0.1" /> |
| <dynamics damping="100.0" /> |
| </joint> |
| |
| <link name="head_pan_link"> |
| <inertial> |
| <origin rpy="0 0 0" xyz="0.0321 0.0161 0.0390" /> |
| <mass value="2.2556" /> |
| <inertia ixx="0.0129" ixy="0.0002" ixz="0.0007" iyy="0.0095" iyz="-0.0" izz="0.0184" /> |
| </inertial> |
| <visual> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/head_pan_link.obj" /> |
| </geometry> |
| </visual> |
| <collision> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/head_pan_link_collision.STL" /> |
| </geometry> |
| </collision> |
| </link> |
| <joint name="head_pan_joint" type="revolute"> |
| <origin rpy="0 0 0" xyz="0.053125 0 0.603001417713939" /> |
| <parent link="torso_lift_link" /> |
| <child link="head_pan_link" /> |
| <axis xyz="0 0 1" /> |
| <limit effort="0.32" lower="-1.57" upper="1.57" velocity="1.57" /></joint> |
| <link name="head_tilt_link"> |
| <inertial> |
| <origin rpy="0 0 0" xyz="0.0081 0.0025 0.0113" /> |
| <mass value="0.9087" /> |
| <inertia ixx="0.0061" ixy="-0.0" ixz="0.0002" iyy="0.0014" iyz="-0.0001" izz="0.0061" /> |
| </inertial> |
| <visual> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/head_tilt_link.obj" /> |
| </geometry> |
| </visual> |
| <collision> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/head_tilt_link_collision.STL" /> |
| </geometry> |
| </collision> |
| </link> |
| <joint name="head_tilt_joint" type="revolute"> |
| <origin rpy="0 0.2617993877991494 0" xyz="0.14253 0 0.057999" /> |
| <parent link="head_pan_link" /> |
| <child link="head_tilt_link" /> |
| <axis xyz="0 1 0" /> |
| <limit effort="0.68" lower="-0.76" upper="1.45" velocity="1.57" /> |
| </joint> |
| <link name="shoulder_pan_link"> |
| <inertial> |
| <origin rpy="0 0 0" xyz="0.0927 -0.0056 0.0564" /> |
| <mass value="2.5587" /> |
| <inertia ixx="0.0043" ixy="-0.0001" ixz="0.001" iyy="0.0087" iyz="-0.0001" izz="0.0087" /> |
| </inertial> |
| <visual> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/shoulder_pan_link.obj" /> |
| </geometry> |
| </visual> |
| <collision> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/shoulder_pan_link_collision.STL" /> |
| </geometry> |
| </collision> |
| </link> |
| <joint name="shoulder_pan_joint" type="revolute"> |
| <origin rpy="0 0 0" xyz="0.119525 0 0.34858" /> |
| <parent link="torso_lift_link" /> |
| <child link="shoulder_pan_link" /> |
| <axis xyz="0 0 1" /> |
| <dynamics damping="1.0" /> |
| <limit effort="33.82" lower="-1.6056" upper="1.6056" velocity="1.256" /> |
| </joint> |
| <link name="shoulder_lift_link"> |
| <inertial> |
| <origin rpy="0 0 0" xyz="0.1432 0.0072 -0.0001" /> |
| <mass value="2.6615" /> |
| <inertia ixx="0.0028" ixy="-0.0021" ixz="-0.0" iyy="0.0111" iyz="-0.0" izz="0.0112" /> |
| </inertial> |
| <visual> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/shoulder_lift_link.obj" /> |
| </geometry> |
| </visual> |
| <collision> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/shoulder_lift_link_collision.STL" /> |
| </geometry> |
| </collision> |
| </link> |
| <joint name="shoulder_lift_joint" type="revolute"> |
| <origin rpy="0 0 0" xyz="0.117 0 0.0599999999999999" /> |
| <parent link="shoulder_pan_link" /> |
| <child link="shoulder_lift_link" /> |
| <axis xyz="0 1 0" /> |
| <dynamics damping="1.0" /> |
| <limit effort="131.76" lower="-1.221" upper="1.518" velocity="1.454" /> |
| </joint> |
| <link name="upperarm_roll_link"> |
| <inertial> |
| <origin rpy="0 0 0" xyz="0.1165 0.0014 0.0000" /> |
| <mass value="2.3311" /> |
| <inertia ixx="0.0019" ixy="-0.0001" ixz="0.0" iyy="0.0045" iyz="0.0" izz="0.0047" /> |
| </inertial> |
| <visual> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/upperarm_roll_link.obj" /> |
| </geometry> |
| </visual> |
| <collision> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/upperarm_roll_link_collision.STL" /> |
| </geometry> |
| </collision> |
| </link> |
| <joint name="upperarm_roll_joint" type="revolute"> |
| <origin rpy="0 0 0" xyz="0.219 0 0" /> |
| <parent link="shoulder_lift_link" /> |
| <child link="upperarm_roll_link" /> |
| <axis xyz="1 0 0" /> |
| <dynamics damping="5.0" /> |
| <limit effort="76.94" lower="-6.283185307179586" upper="6.283185307179586" velocity="1.571" /> |
| </joint> |
| <link name="elbow_flex_link"> |
| <inertial> |
| <origin rpy="0 0 0" xyz="0.1279 0.0073 0.0000" /> |
| <mass value="2.1299" /> |
| <inertia ixx="0.0024" ixy="-0.0016" ixz="0.0" iyy="0.0082" iyz="-0.0" izz="0.0084" /> |
| </inertial> |
| <visual> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/elbow_flex_link.obj" /> |
| </geometry> |
| </visual> |
| <collision> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/elbow_flex_link_collision.STL" /> |
| </geometry> |
| </collision> |
| </link> |
| <joint name="elbow_flex_joint" type="revolute"> |
| <origin rpy="0 0 0" xyz="0.133 0 0" /> |
| <parent link="upperarm_roll_link" /> |
| <child link="elbow_flex_link" /> |
| <axis xyz="0 1 0" /> |
| <dynamics damping="1.0" /> |
| <limit effort="66.18" lower="-2.251" upper="2.251" velocity="1.521" /> |
| </joint> |
| <link name="forearm_roll_link"> |
| <inertial> |
| <origin rpy="0 0 0" xyz="0.1097 -0.0266 0.0000" /> |
| <mass value="1.6563" /> |
| <inertia ixx="0.0016" ixy="-0.0003" ixz="0.0" iyy="0.003" iyz="-0.0" izz="0.0035" /> |
| </inertial> |
| <visual> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/forearm_roll_link.obj" /> |
| </geometry> |
| </visual> |
| <collision> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/forearm_roll_link_collision.STL" /> |
| </geometry> |
| </collision> |
| </link> |
| <joint name="forearm_roll_joint" type="revolute"> |
| <origin rpy="0 0 0" xyz="0.197 0 0" /> |
| <parent link="elbow_flex_link" /> |
| <child link="forearm_roll_link" /> |
| <axis xyz="1 0 0" /> |
| <dynamics damping="5.0" /> |
| <limit effort="29.35" lower="-6.283185307179586" upper="6.283185307179586" velocity="1.571" /> |
| </joint> |
| <link name="wrist_flex_link"> |
| <inertial> |
| <origin rpy="0 0 0" xyz="0.0882 0.0009 -0.0001" /> |
| <mass value="1.725" /> |
| <inertia ixx="0.0018" ixy="-0.0001" ixz="-0.0" iyy="0.0042" iyz="0.0" izz="0.0042" /> |
| </inertial> |
| <visual> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/wrist_flex_link.obj" /> |
| </geometry> |
| </visual> |
| <collision> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/wrist_flex_link_collision.STL" /> |
| </geometry> |
| </collision> |
| </link> |
| <joint name="wrist_flex_joint" type="revolute"> |
| <origin rpy="0 0 0" xyz="0.1245 0 0" /> |
| <parent link="forearm_roll_link" /> |
| <child link="wrist_flex_link" /> |
| <axis xyz="0 1 0" /> |
| <dynamics damping="1.0" /> |
| <limit effort="25.7" lower="-2.16" upper="2.16" velocity="2.268" /> |
| </joint> |
| <link name="wrist_roll_link"> |
| <inertial> |
| <origin rpy="0 0 0" xyz="0.0095 0.0004 -0.0002" /> |
| <mass value="0.1354" /> |
| <inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001" /> |
| </inertial> |
| <visual> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/wrist_roll_link.obj" /> |
| </geometry> |
| </visual> |
| <collision> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/wrist_roll_link_collision.STL" /> |
| </geometry> |
| </collision> |
| </link> |
| <joint name="wrist_roll_joint" type="revolute"> |
| <origin rpy="0 0 0" xyz="0.1385 0 0" /> |
| <parent link="wrist_flex_link" /> |
| <child link="wrist_roll_link" /> |
| <axis xyz="1 0 0" /> |
| <limit effort="7.36" lower="-6.283185307179586" upper="6.283185307179586" velocity="2.268" /> |
| <dynamics damping="5.0" /> |
| </joint> |
| <link name="gripper_link"> |
| <inertial> |
| <origin rpy="0 0 0" xyz="-0.0900 -0.0001 -0.0017" /> |
| <mass value="1.5175" /> |
| <inertia ixx="0.0013" ixy="-0.0" ixz="0.0" iyy="0.0019" iyz="-0.0" izz="0.0024" /> |
| </inertial> |
| <visual> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/gripper_link.obj" /> |
| </geometry> |
| </visual> |
| <collision> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/gripper_link.obj" /> |
| </geometry> |
| </collision> |
| </link> |
| <joint name="gripper_axis" type="fixed"> |
| <origin rpy="0 0 0" xyz="0.16645 0 0" /> |
| <parent link="wrist_roll_link" /> |
| <child link="gripper_link" /> |
| <axis xyz="0 1 0" /> |
| </joint> |
| <link name="r_gripper_finger_link"> |
| <inertial> |
| <origin rpy="0 0 0" xyz="-0.01 0 0" /> |
| <mass value="0.0798" /> |
| <inertia ixx="0.002" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" /> |
| </inertial> |
|
|
| <visual> |
| <origin rpy="0 0 0" xyz="0 -0.01 0" /> |
| <geometry> |
| <box size="0.06 0.015 0.045"/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin rpy="0 0 0" xyz="0 -0.01 0" /> |
| <geometry> |
| <box size="0.06 0.015 0.045"/> |
| </geometry> |
| </collision> |
|
|
|
|
| </link> |
| <joint name="r_gripper_finger_joint" type="prismatic"> |
| <origin rpy="0 0 0" xyz="0 0.015425 0" /> |
| <parent link="gripper_link" /> |
| <child link="r_gripper_finger_link" /> |
| <axis xyz="0 1 0" /> |
| <limit effort="60" lower="0.0" upper="0.05" velocity="0.25" /> |
| <dynamics damping="0.0" friction="1.0"/> |
| </joint> |
| <link name="l_gripper_finger_link"> |
| <inertial> |
| <origin rpy="0 0 0" xyz="-0.01 0 0" /> |
| <mass value="0.0798" /> |
| <inertia ixx="0.002" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" /> |
| </inertial> |
|
|
|
|
| <visual> |
| <origin rpy="0 0 0" xyz="0 0.01 0" /> |
| <geometry> |
| <box size="0.06 0.015 0.045"/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin rpy="0 0 0" xyz="0 0.01 0" /> |
| <geometry> |
| <box size="0.06 0.015 0.045"/> |
| </geometry> |
| </collision> |
|
|
|
|
|
|
| </link> |
| <joint name="l_gripper_finger_joint" type="prismatic"> |
| <origin rpy="0 0 0" xyz="0 -0.015425 0" /> |
| <parent link="gripper_link" /> |
| <child link="l_gripper_finger_link" /> |
| <axis xyz="0 -1 0" /> |
| <limit effort="60" lower="0.0" upper="0.05" velocity="0.25" /> |
| <dynamics damping="0.0" friction="1.0"/> |
| </joint> |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| <link name="estop_link"> |
| <inertial> |
| <origin rpy="0 0 0" xyz="0.002434512737072 -0.00330608315239905 0.00665139196650039" /> |
| <mass value="0.00196130439134723" /> |
| <inertia ixx="3.02810026604417E-07" ixy="-1.5862023118056E-08" ixz="3.16561396557437E-08" iyy="2.93322917127605E-07" iyz="-4.28833522751273E-08" izz="2.28513272627183E-07" /> |
| </inertial> |
| <visual> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/estop_link.obj" /> |
| </geometry> |
| <material name=""> |
| <color rgba="0.8 0 0 1" /> |
| </material> |
| </visual> |
| <collision> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/estop_link.obj" /> |
| </geometry> |
| </collision> |
| </link> |
| <joint name="estop_joint" type="fixed"> |
| <origin rpy="1.5708 0 0" xyz="-0.12465 0.23892 0.31127" /> |
| <parent link="base_link" /> |
| <child link="estop_link" /> |
| <axis xyz="0 0 0" /> |
| </joint> |
| <link name="laser_link"> |
| <inertial> |
| <origin rpy="0 0 0" xyz="-0.0306228970175641 0.0007091682908278 0.0551974119471302" /> |
| <mass value="0.00833634573995571" /> |
| <inertia ixx="1.01866461240801E-06" ixy="-5.88447626567756E-08" ixz="7.83857244757914E-08" iyy="5.10039589974707E-07" iyz="-7.12664289617235E-09" izz="1.28270671527309E-06" /> |
| </inertial> |
| <visual> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/laser_link.obj" /> |
| </geometry> |
| </visual> |
| <collision> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/laser_link.obj" /> |
| </geometry> |
| </collision> |
| </link> |
| <joint name="laser_joint" type="fixed"> |
| <origin rpy="3.14159265359 0 0" xyz="0.235 0 0.2878" /> |
| <parent link="base_link" /> |
| <child link="laser_link" /> |
| <axis xyz="0 0 0" /> |
| </joint> |
| <link name="torso_fixed_link"> |
| <inertial> |
| <origin rpy="0 0 0" xyz="-0.0722 0.0057 0.2656" /> |
| <mass value="13.2775" /> |
| <inertia ixx="0.3861" ixy="0.0015" ixz="-0.0102" iyy="0.3388" iyz="0.0117" izz="0.1018" /> |
| </inertial> |
| <visual> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/torso_fixed_link.obj" /> |
| </geometry> |
| </visual> |
| <collision> |
| <origin rpy="0 0 0" xyz="0 0 0" /> |
| <geometry> |
| <mesh filename="meshes/torso_fixed_link.obj" /> |
| </geometry> |
| </collision> |
| </link> |
| <joint name="torso_fixed_joint" type="fixed"> |
| <origin rpy="-6.12303176911189E-17 0 0" xyz="-0.086875 0 0.377425" /> |
| <parent link="base_link" /> |
| <child link="torso_fixed_link" /> |
| <axis xyz="0 1 0" /> |
| </joint> |
| <link name="head_camera_link"> |
| <inertial> |
| <mass value="0.0001"/> |
| <origin rpy="0 0 0" xyz="0 0 0"/> |
| <inertia ixx="0.0000001" ixy="0.0" ixz="0.0" iyy="0.0000001" iyz="0.0" izz="0.0000001"/> |
| </inertial> |
| </link> |
| <joint name="head_camera_joint" type="fixed"> |
| <origin rpy="0 0 0" xyz="0.055 0 0.0225" /> |
| <parent link="head_tilt_link" /> |
| <child link="head_camera_link" /> |
| </joint> |
| <link name="head_camera_rgb_frame"> |
| <inertial> |
| <mass value="0.0001"/> |
| <origin rpy="0 0 0" xyz="0 0 0"/> |
| <inertia ixx="0.0000001" ixy="0.0" ixz="0.0" iyy="0.0000001" iyz="0.0" izz="0.0000001"/> |
| </inertial> |
| </link> |
| <joint name="head_camera_rgb_joint" type="fixed"> |
| <origin rpy="0 0 0" xyz="0 0.02 0" /> |
| <parent link="head_camera_link" /> |
| <child link="head_camera_rgb_frame" /> |
| </joint> |
| <link name="head_camera_rgb_optical_frame"> |
| <inertial> |
| <mass value="0.0001"/> |
| <origin rpy="0 0 0" xyz="0 0 0"/> |
| <inertia ixx="0.0000001" ixy="0.0" ixz="0.0" iyy="0.0000001" iyz="0.0" izz="0.0000001"/> |
| </inertial> |
| </link> |
| <joint name="head_camera_rgb_optical_joint" type="fixed"> |
| <origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0 0" /> |
| <parent link="head_camera_rgb_frame" /> |
| <child link="head_camera_rgb_optical_frame" /> |
| </joint> |
| <link name="head_camera_depth_frame"> |
| <inertial> |
| <mass value="0.0001"/> |
| <origin rpy="0 0 0" xyz="0 0 0"/> |
| <inertia ixx="0.0000001" ixy="0.0" ixz="0.0" iyy="0.0000001" iyz="0.0" izz="0.0000001"/> |
| </inertial> |
| </link> |
| <joint name="head_camera_depth_joint" type="fixed"> |
| <origin rpy="0 0 0" xyz="0 0.045 0" /> |
| <parent link="head_camera_link" /> |
| <child link="head_camera_depth_frame" /> |
| </joint> |
| <link name="head_camera_depth_optical_frame"> |
| <inertial> |
| <mass value="0.0001"/> |
| <origin rpy="0 0 0" xyz="0 0 0"/> |
| <inertia ixx="0.0000001" ixy="0.0" ixz="0.0" iyy="0.0000001" iyz="0.0" izz="0.0000001"/> |
| </inertial> |
| </link> |
| <joint name="head_camera_depth_optical_joint" type="fixed"> |
| <origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0 0" /> |
| <parent link="head_camera_depth_frame" /> |
| <child link="head_camera_depth_optical_frame" /> |
| </joint> |
| <link name="eyes"> |
| <inertial> |
| <mass value="0.001"/> |
| <origin xyz="0 0 0"/> |
| <inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001"/> |
| </inertial> |
| </link> |
| <joint name="eye_joint" type="fixed"> |
| <origin rpy="0 0 0" xyz="0 0 0"/> |
| <parent link="head_camera_link"/> |
| <child link="eyes"/> |
| </joint> |
|
|
| </robot> |
|
|