hab_stretch / urdf /hab_stretch.urdf
aclegg3
actual file commit
3a1fd52
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from /home/cpaxton/catkin_ws/src/stretch_ros/stretch_description/urdf/stretch_description.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="stretch_description">
<link name="link_wrist_yaw_bottom">
<inertial>
<origin rpy="0 0 0" xyz="-0.012839101377342 -0.0382787718640742 -0.0228400332263617"/>
<mass value="0.0988906816399982"/>
<inertia ixx="2.60067866573596E-05" ixy="-6.73176267521354E-06" ixz="-2.43476436723672E-06" iyy="5.99482946819923E-06" iyz="-3.39642410492401E-06" izz="2.56907114334732E-05"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_wrist_yaw_bottom.STL"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<!--collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_wrist_yaw_bottom.STL"/>
</geometry>
</collision-->
<collision>
<origin rpy="1.570796 1.570796 0.000000" xyz="-0.013291 -0.021400 -0.020750"/>
<geometry>
<box size="0.041500 0.062919 0.094300"/>
</geometry>
</collision>
</link>
<joint name="joint_wrist_yaw_bottom" type="fixed">
<origin rpy="-3.14159265358979 1.13367999021379E-14 1.57079632679489" xyz="0 0 0"/>
<parent link="link_wrist_yaw"/>
<child link="link_wrist_yaw_bottom"/>
<axis xyz="0 0 0"/>
</joint>
<link name="link_wrist_pitch">
<inertial>
<origin rpy="0 0 0" xyz="-0.00310609611067142 -0.0150777141465843 0.0204734587925901"/>
<mass value="0.0701267146295583"/>
<inertia ixx="2.55965614980905E-06" ixy="-1.47551515167608E-06" ixz="-6.31436085977252E-08" iyy="3.43968637386282E-06" iyz="-4.17813567208843E-07" izz="4.53568668211393E-06"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_wrist_pitch.STL"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<!--collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_wrist_pitch.STL"/>
</geometry>
</collision-->
<collision>
<origin rpy="1.570796 1.570796 0.000000" xyz="-0.006179 -0.012056 0.020731"/>
<geometry>
<box size="0.043138 0.053359 0.064888"/>
</geometry>
</collision>
</link>
<joint name="joint_wrist_pitch" type="revolute">
<origin rpy="1.5707963267949 -8.12895570882604E-15 -3.14159265358979" xyz="0 -0.0195500000000002 -0.0247499999999984"/>
<parent link="link_wrist_yaw_bottom"/>
<child link="link_wrist_pitch"/>
<axis xyz="0 0 -1"/>
<limit effort="100" lower="-1.57" upper="0.56" velocity="1.0"/>
</joint>
<link name="link_wrist_roll">
<inertial>
<origin rpy="0 0 0" xyz="9.63118473862323E-15 -6.38378239159465E-15 0.00768048802649798"/>
<mass value="0.00585666394358811"/>
<inertia ixx="2.55965614980905E-06" ixy="-1.47551515167608E-06" ixz="-6.31436085977252E-08" iyy="3.43968637386282E-06" iyz="-4.17813567208843E-07" izz="4.53568668211393E-06"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_wrist_roll.STL"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<!--collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_wrist_roll.STL"/>
</geometry>
</collision-->
<collision>
<origin rpy="-1.157430 1.570796 0.000000" xyz="-0.000000 -0.000000 0.007750"/>
<geometry>
<box size="0.015500 0.028888 0.028987"/>
</geometry>
</collision>
</link>
<joint name="joint_wrist_roll" type="revolute">
<origin rpy="3.14159265358979 1.5707963267949 0" xyz="-0.0188587444076125 -0.0239999999998942 0.01955"/>
<parent link="link_wrist_pitch"/>
<child link="link_wrist_roll"/>
<axis xyz="0 0 1"/>
<limit effort="100" lower="-3.14" upper="3.14" velocity="1.0"/>
</joint>
<link name="link_straight_gripper">
<inertial>
<origin rpy="0 0 0" xyz="0.00150764845432383 -0.00711581846201287 0.0399737901417758"/>
<mass value="0.0496384234458284"/>
<inertia ixx="5.61461154156397E-06" ixy="8.29518962984231E-07" ixz="-2.41382921888194E-06" iyy="1.11504692003467E-05" iyz="9.76174898123369E-07" izz="6.63803357903882E-06"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_straight_gripper.STL"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<!--collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_straight_gripper.STL"/>
</geometry>
</collision-->
<collision>
<origin rpy="0.010085 0.000000 3.141593" xyz="-0.000000 -0.013998 0.054277"/>
<geometry>
<box size="0.052858 0.056076 0.108538"/>
</geometry>
</collision>
</link>
<joint name="joint_straight_gripper" type="fixed">
<origin rpy="3.54987407349455E-30 3.24021254484265E-20 -3.14159265358979" xyz="0 0 0.0155"/>
<parent link="link_wrist_roll"/>
<child link="link_straight_gripper"/>
<axis xyz="0 0 0"/>
</joint>
<link name="link_gripper_finger_right">
<inertial>
<origin rpy="0 0 0" xyz="-0.094981 -0.0080152 -2.2204E-16"/>
<mass value="0.047621"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_gripper_finger_right.obj"/>
</geometry>
<!-- <material name="">
<color rgba="0.79216 0.81961 0.93333 1"/>
</material> -->
</visual>
<!--collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_gripper_finger_right.STL"/>
</geometry>
</collision-->
<collision>
<origin rpy="-0.063447 1.570796 0.000000" xyz="-0.097587 -0.014600 0.000000"/>
<geometry>
<box size="0.013000 0.030210 0.196835"/>
</geometry>
</collision>
</link>
<joint name="joint_gripper_finger_right" type="revolute">
<origin rpy="1.5708 1.5708 0" xyz="-0.018599 0.003 0.033689"/>
<parent link="link_straight_gripper"/>
<child link="link_gripper_finger_right"/>
<axis xyz="0 0 1"/>
<limit effort="100" lower="-0.6" upper="0.6" velocity="1.0"/>
</joint>
<link name="link_gripper_fingertip_right">
<inertial>
<origin rpy="0 0 0" xyz="2.83785970833783E-08 6.75131661687089E-09 0.00812578923434215"/>
<mass value="0.00382160881468841"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_gripper_fingertip_right.obj"/>
</geometry>
<!-- <material name="">
<color rgba="0.250980392156863 0.250980392156863 0.250980392156863 1"/>
</material> -->
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_gripper_fingertip_right.obj"/>
</geometry>
</collision>
</link>
<joint name="joint_gripper_fingertip_right" type="fixed">
<origin rpy="-1.57079632679483 -3.43320051448326E-14 0.540456056432235" xyz="-0.190596948563868 -0.015 0"/>
<parent link="link_gripper_finger_right"/>
<child link="link_gripper_fingertip_right"/>
<axis xyz="0 0 0"/>
</joint>
<link name="link_gripper_finger_left">
<inertial>
<origin rpy="0 0 0" xyz="0.0949811095686165 -0.00801522758203194 1.38777878078145E-15"/>
<mass value="0.0476207785199479"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<visual>
<origin rpy="3.141592653589793 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_gripper_finger_left.obj"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<!--collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_gripper_finger_left.STL"/>
</geometry>
</collision-->
<collision>
<origin rpy="3.078145 1.570796 0.000000" xyz="0.097587 0.014600 0.000000"/>
<geometry>
<box size="0.013000 0.030210 0.196835"/>
</geometry>
</collision>
</link>
<joint name="joint_gripper_finger_left" type="revolute">
<origin rpy="1.5708 -1.5708 0" xyz="0.018599 0.003 0.033689"/>
<parent link="link_straight_gripper"/>
<child link="link_gripper_finger_left"/>
<axis xyz="0 0 -1"/>
<limit effort="100" lower="-0.6" upper="0.6" velocity="1.0"/>
</joint>
<link name="link_gripper_fingertip_left">
<inertial>
<origin rpy="0 0 0" xyz="-2.59496317767116E-08 -6.65612598371723E-09 0.00812579036862837"/>
<mass value="0.00382160686584851"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_gripper_fingertip_left.obj"/>
</geometry>
<!-- <material name="">
<color rgba="0.250980392156863 0.250980392156863 0.250980392156863 1"/>
</material> -->
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_gripper_fingertip_left.obj"/>
</geometry>
</collision>
</link>
<joint name="joint_gripper_fingertip_left" type="fixed">
<origin rpy="1.57079632679496 4.51275387511463E-14 2.60113659715756" xyz="0.190596948563868 -0.015 0"/>
<parent link="link_gripper_finger_left"/>
<child link="link_gripper_fingertip_left"/>
<axis xyz="0 0 0"/>
</joint>
<!--<xacro:include filename="stretch_gripper.xacro" /> -->
<!--<xacro:include filename="stretch_gripper_with_puller.xacro" />-->
<!--<xacro:include filename="stretch_dry_erase_marker.xacro" />-->
<link name="base_link">
<inertial>
<origin rpy="1.5607 0 0"
xyz="-0.109461304328163 -0.000741018909047708 0.0914915269429946"/>
<!--mass value="1.0723782659782"/-->
<mass value="10.0723782659782"/>
<inertia ixx="0.00310580907710135" ixy="1.5182848191076E-06" ixz="0.00041690466732394" iyy="0.00433798719991832" iyz="1.33487716258445E-05" izz="0.0037204727467362"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/base_link.obj"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<!--collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/base_link.STL"/>
</geometry>
</collision-->
<collision>
<origin rpy="-1.570796 1.570796 0.0" xyz="-0.117155 0.000075 0.078399"/>
<geometry>
<box size="0.143197 0.324688 0.361202"/>
</geometry>
</collision>
</link>
<link name="link_right_wheel">
<inertial>
<origin rpy="0 0 0" xyz="1.25554620866719E-07 3.54748938447003E-07 0.0239581106165018"/>
<mass value="0.01"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_right_wheel.obj"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<!--collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_right_wheel.STL"/>
</geometry>
</collision-->
</link>
<joint name="joint_right_wheel" type="continuous">
<origin rpy="-1.57079632679489 -1.11022302462516E-16 7.28583859910277E-17" xyz="-0.00300000000000034 -0.15765 0.0508000000000004"/>
<parent link="base_link"/>
<child link="link_right_wheel"/>
<axis xyz="0 0 1"/>
<dynamics damping="21.75" friction="10.48" spring_reference="0" spring_stiffness="{joint_spring_stiffness}"/>
</joint>
<link name="link_left_wheel">
<inertial>
<origin rpy="0 0 0" xyz="1.2555462092223E-07 -3.54748938502514E-07 -0.0239581106165035"/>
<mass value="0.01"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_left_wheel.obj"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<!--collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_left_wheel.STL"/>
</geometry>
</collision-->
</link>
<joint name="joint_left_wheel" type="continuous">
<origin rpy="-1.5707963267949 3.16227047920818E-31 7.88745438253713E-16" xyz="-0.00300000000001899 0.15765 0.0507999999999994"/>
<parent link="base_link"/>
<child link="link_left_wheel"/>
<axis xyz="0 0 1"/>
<dynamics damping="21.75" friction="10.48" spring_reference="0" spring_stiffness="{joint_spring_stiffness}"/>
</joint>
<link name="caster_link">
<!--collision>
<geometry>
<sphere radius="0.032"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<slip1>1.0</slip1>
<slip2>1.0</slip2>
</ode>
</friction>
</surface>
</collision-->
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/omni_wheel_m.obj"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<inertial>
<mass value="0.01"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
</link>
<joint name="caster_joint" type="fixed">
<parent link="base_link"/>
<child link="caster_link"/>
<origin rpy="-1.5707963267948966 0 0" xyz="-0.245 0.0 0.032"/>
<axis xyz="0 0 1"/>
</joint>
<link name="link_mast">
<inertial>
<origin rpy="0 0 0" xyz="0.00755818572975822 0.773971284176834 0.00647313086620024"/>
<mass value="0.749143203376401"/>
<inertia ixx="0.0709854511954588" ixy="-0.00433428742758457" ixz="-0.000186110788697573" iyy="0.000437922053342648" iyz="-0.00288788257713431" izz="0.071104808501661"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_mast.obj"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<!--collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_mast.STL"/>
</geometry>
</collision-->
<collision>
<origin rpy="1.570796 1.570796 -0.000000" xyz="-0.000000 0.707500 0."/>
<geometry>
<box size="0.038125 0.038125 1.285000"/>
</geometry>
</collision>
</link>
<joint name="joint_mast" type="fixed">
<origin rpy="1.5707963267949 0 0.00925318926571245" xyz="-0.07 0.134999999999998 0.0284000000000001"/>
<parent link="base_link"/>
<child link="link_mast"/>
<axis xyz="0 0 0"/>
</joint>
<link name="link_lift">
<inertial>
<origin rpy="0 0 0" xyz="-0.0547636346252869 0.0380939689802074 0.00933159404448308"/>
<mass value="0.444820831236007"/>
<inertia ixx="0.000567192946271367" ixy="-0.00024607534789508" ixz="-0.000128108442260574" iyy="0.00127108364478659" iyz="7.61916855070339E-06" izz="0.00137296635099006"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_lift.obj"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<!--collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_lift.STL"/>
</geometry>
</collision-->
<collision>
<origin rpy="-2.192103 1.570796 0.000000" xyz="-0.030334 0.039510 0.026256"/>
<geometry>
<box size="0.120261 0.137963 0.258855"/>
</geometry>
</collision>
</link>
<joint name="joint_lift" type="prismatic">
<origin rpy="-1.57079632679552 1.5615431375292 -6.2942004366467E-13" xyz="-0.0369217062323472 0.165471199999996 -0.000341653286793524"/>
<parent link="link_mast"/>
<child link="link_lift"/>
<axis xyz="0 0 1"/>
<!-- for now: hand copied range_m: from lift: from ~/repos/stretch_fleet/stretch-re1-1001/stretch_re1_factory_params.yaml -->
<!--<limit effort="100" lower="0.0" upper="1.095" velocity="1.0"/>-->
<!-- copied value did not reach the top of mesh model with GUI sliders and RViz -->
<limit effort="100" lower="0.0" upper="1.1" velocity="1.0"/>
</joint>
<link name="link_arm_l4">
<inertial>
<origin rpy="0 0 0" xyz="-1.61247276464493E-06 1.54715589201215E-06 -0.0953252706040035"/>
<mass value="0.0676525455789735"/>
<inertia ixx="0.000122002023066796" ixy="7.29593356230121E-13" ixz="9.63170353371061E-09" iyy="0.000122002023127152" iyz="-9.24154949889042E-09" izz="1.46043439809638E-12"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_arm_l4.obj"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<!--collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_arm_l4.STL"/>
</geometry>
</collision-->
<collision>
<origin rpy="-3.141593 0.000000 -1.570796" xyz="-0.000000 0.000000 -0.111250"/>
<geometry>
<box size="0.059250 0.059250 0.222500"/>
</geometry>
</collision>
</link>
<joint name="joint_arm_l4" type="fixed">
<origin rpy="1.5708 -3.1019E-16 -1.5708" xyz="-0.25471 0 0"/>
<parent link="link_lift"/>
<child link="link_arm_l4"/>
<axis xyz="0 0 0"/>
</joint>
<link name="link_arm_l3">
<inertial>
<origin rpy="0 0 0" xyz="-3.34873468621488E-07 4.7411336306924E-07 -0.0974069598289041"/>
<mass value="0.0626921047058405"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_arm_l3.obj"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<!--collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_arm_l3.STL"/>
</geometry>
</collision-->
<collision>
<origin rpy="0.000000 -0.000000 -1.570796" xyz="0.000000 -0.000000 -0.113250"/>
<geometry>
<box size="0.055250 0.055250 0.226500"/>
</geometry>
</collision>
</link>
<joint name="joint_arm_l3" type="prismatic">
<origin rpy="3.5742E-16 3.2123E-16 -2.4565E-16" xyz="0 0 0.013"/>
<parent link="link_arm_l4"/>
<child link="link_arm_l3"/>
<axis xyz="0 0 1"/>
<!-- 0.13 = 0.52/4-->
<limit effort="100" lower="0.0" upper="0.13" velocity="1.0"/>
</joint>
<link name="link_arm_l2">
<inertial>
<origin rpy="0 0 0" xyz="-3.31043560508615E-07 3.13422303999111E-07 -0.097255883541891"/>
<mass value="0.0569074368576238"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_arm_l2.obj"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<!--collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_arm_l2.STL"/>
</geometry>
</collision-->
<collision>
<origin rpy="-3.141593 0.000000 -1.570796" xyz="-0.000000 -0.000000 -0.113250"/>
<geometry>
<box size="0.051250 0.051250 0.226500"/>
</geometry>
</collision>
</link>
<joint name="joint_arm_l2" type="prismatic">
<origin rpy="2.91385731014123E-16 4.44300759504684E-17 3.25691080516352E-16" xyz="0 0 0.013"/>
<parent link="link_arm_l3"/>
<child link="link_arm_l2"/>
<axis xyz="0 0 1"/>
<!-- 0.13 = 0.52/4-->
<limit effort="100" lower="0.0" upper="0.13" velocity="1.0"/>
</joint>
<link name="link_arm_l1">
<inertial>
<origin rpy="0 0 0" xyz="-3.36876635420591E-07 3.05876091066803E-07 -0.0969117032232756"/>
<mass value="0.0511763619538321"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_arm_l1.obj"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<!--collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_arm_l1.STL"/>
</geometry>
</collision-->
<collision>
<origin rpy="-3.141593 0.000000 -1.570796" xyz="0.000000 -0.000000 -0.113250"/>
<geometry>
<box size="0.047250 0.047250 0.226500"/>
</geometry>
</collision>
</link>
<joint name="joint_arm_l1" type="prismatic">
<origin rpy="7.41596560408007E-17 1.33876788296791E-16 -2.44545873596083E-16" xyz="0 0 0.013"/>
<parent link="link_arm_l2"/>
<child link="link_arm_l1"/>
<axis xyz="0 0 1"/>
<!-- 0.13 = 0.52/4-->
<limit effort="100" lower="0.0" upper="0.13" velocity="1.0"/>
</joint>
<link name="link_arm_l0">
<inertial>
<origin rpy="0 0 0" xyz="0.0230715049668191 -0.00195115833662818 -0.0360646347160285"/>
<mass value="0.101241250325294"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_arm_l0.obj"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<!--collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_arm_l0.STL"/>
</geometry>
</collision-->
<collision>
<origin rpy="-3.141593 0.000000 -1.570796" xyz="0.041161 -0.000358 -0.086500"/>
<geometry>
<box size="0.059285 0.127573 0.226500"/>
</geometry>
</collision>
</link>
<joint name="joint_arm_l0" type="prismatic">
<origin rpy="-3.05317390622457E-16 -4.23236224076729E-16 -2.68425135229209E-17" xyz="0 0 -0.0137499999999938"/>
<parent link="link_arm_l1"/>
<child link="link_arm_l0"/>
<axis xyz="0 0 1"/>
<!-- 0.13 = 0.52/4-->
<limit effort="100" lower="0.0" upper="0.13" velocity="1.0"/>
</joint>
<link name="link_wrist_yaw">
<inertial>
<origin rpy="0 0 0" xyz="-8.02795716750571E-06 1.93811447768422E-05 0.018946700595851"/>
<mass value="0.0405398981326229"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_wrist_yaw.obj"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<!--collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_wrist_yaw.STL"/>
</geometry>
</collision-->
<collision>
<origin rpy="-3.141593 0.000000 0.432976" xyz="-0.000022 -0.000010 -0.019000"/>
<geometry>
<box size="0.029951 0.029976 0.038000"/>
</geometry>
</collision>
</link>
<joint name="joint_wrist_yaw" type="revolute">
<origin rpy="1.5708 4.2595E-14 2.6415E-15" xyz="0.083 -0.03075 0"/>
<parent link="link_arm_l0"/>
<child link="link_wrist_yaw"/>
<axis xyz="0 0 -1"/>
<!--
stowed to front ~225 deg: 3.15159 x 1.25 = 3.9395
using 4.0
stowed to back ~100 deg: 100 / 180 x 3.14159 = 1.7453
using -1.75
-->
<limit effort="100" lower="-1.75" upper="4.0" velocity="1.0"/>
</joint>
<link name="link_head">
<inertial>
<origin rpy="0 0 0" xyz="0.0372933550588956 0.045509432985552 0.0281136801213409"/>
<mass value="0.129454717596498"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_head.obj"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<!--collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_head.STL"/>
</geometry>
</collision-->
<collision>
<origin rpy="0.158839 1.570692 0.181780" xyz="0.061219 0.028457 0.028216"/>
<geometry>
<box size="0.056453 0.131612 0.195150"/>
</geometry>
</collision>
</link>
<joint name="joint_head" type="fixed">
<origin rpy="1.5708 -1.5615 3.1416" xyz="0 1.33 0"/>
<parent link="link_mast"/>
<child link="link_head"/>
<axis xyz="0 0 0"/>
</joint>
<link name="link_head_pan">
<inertial>
<origin rpy="0 0 0" xyz="-0.00116200255310878 0.0130365621706306 0.00137629842298681"/>
<mass value="0.035858341182617"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_head_pan.obj"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<!--collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_head_pan.STL"/>
</geometry>
</collision-->
<collision>
<origin rpy="0.534070 0.004098 -0.000000" xyz="0.000813 0.017168 -0.011469"/>
<geometry>
<box size="0.043969 0.048193 0.122235"/>
</geometry>
</collision>
</link>
<joint name="joint_head_pan" type="revolute">
<origin rpy="-6.4986E-15 -6.068E-24 1.5708" xyz="0.135 0.0731 -0.003"/>
<parent link="link_head"/>
<child link="link_head_pan"/>
<axis xyz="0 0 1"/>
<!-- unconstrained range for now -->
<limit effort="100" lower="-3.9" upper="1.5" velocity="1.0"/>
</joint>
<link name="link_head_tilt">
<inertial>
<origin rpy="0 0 0" xyz="0.00920211049011871 -0.0279724762416447 0.0306580436227023"/>
<mass value="0.0701242408063442"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_head_tilt.obj"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<!--collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_head_tilt.STL"/>
</geometry>
</collision-->
<collision>
<origin rpy="1.562383 1.569947 -0.008414" xyz="0.010814 -0.023473 0.030498"/>
<geometry>
<box size="0.061014 0.068029 0.120844"/>
</geometry>
</collision>
</link>
<joint name="joint_head_tilt" type="revolute">
<origin rpy="1.5708 6.068E-24 -2.5165E-15" xyz="-0.0013 0.027507 -0.053311"/>
<parent link="link_head_pan"/>
<child link="link_head_tilt"/>
<axis xyz="0 0 1"/>
<!-- unconstrained range for now -->
<limit effort="100" lower="-1.53" upper="0.79" velocity="1.0"/>
</joint>
<link name="link_aruco_right_base">
<inertial>
<origin rpy="0 0 0" xyz="0 0 -5.00000000014378E-07"/>
<mass value="3.59999999990368E-06"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_aruco_right_base.STL"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<!--collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_aruco_right_base.STL"/>
</geometry>
</collision-->
</link>
<joint name="joint_aruco_right_base" type="fixed">
<origin rpy="0 0 -1.5707963267949" xyz="-0.00500000000000014 -0.1304972 0.1597482"/>
<parent link="base_link"/>
<child link="link_aruco_right_base"/>
<axis xyz="0 0 0"/>
</joint>
<link name="link_aruco_left_base">
<inertial>
<origin rpy="0 0 0" xyz="0 0 -5.00000000014378E-07"/>
<mass value="3.59999999990368E-06"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_aruco_left_base.STL"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<!--collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_aruco_left_base.STL"/>
</geometry>
</collision-->
</link>
<joint name="joint_aruco_left_base" type="fixed">
<origin rpy="0 0 -1.5707963267949" xyz="-0.00500000000000014 0.1304972 0.1597482"/>
<parent link="base_link"/>
<child link="link_aruco_left_base"/>
<axis xyz="0 0 0"/>
</joint>
<link name="link_aruco_shoulder">
<inertial>
<origin rpy="0 0 0" xyz="-2.77555756156289E-17 2.56739074444567E-16 -0.000125000000000042"/>
<mass value="0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_aruco_shoulder.STL"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<!--collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_aruco_shoulder.STL"/>
</geometry>
</collision-->
</link>
<joint name="joint_aruco_shoulder" type="fixed">
<origin rpy="-1.53998860117704E-29 3.55962409571165E-15 0.0" xyz="-0.0133768876375287 0.0558540528812078 0.0861368272417975"/>
<parent link="link_lift"/>
<child link="link_aruco_shoulder"/>
<axis xyz="0 0 0"/>
</joint>
<link name="link_aruco_top_wrist">
<inertial>
<origin rpy="0 0 0" xyz="1.11022302462516E-16 3.05311331771918E-16 -0.00012499999999821"/>
<mass value="0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_aruco_top_wrist.STL"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_aruco_top_wrist.STL"/>
</geometry>
</collision>
</link>
<joint name="joint_aruco_top_wrist" type="fixed">
<origin rpy="1.5707963267949 -8.03728587323464E-15 3.14159265358979" xyz="0.0472500000000019 0.0292850000000015 0"/>
<parent link="link_arm_l0"/>
<child link="link_aruco_top_wrist"/>
<axis xyz="0 0 0"/>
</joint>
<link name="link_aruco_inner_wrist">
<inertial>
<origin rpy="0 0 0" xyz="8.32667268468867E-17 1.77635683940025E-15 -0.000125000000000264"/>
<mass value="0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_aruco_inner_wrist.STL"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<!--collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_aruco_inner_wrist.STL"/>
</geometry>
</collision-->
</link>
<joint name="joint_aruco_inner_wrist" type="fixed">
<origin rpy="3.14159265358979 4.23377442363088E-14 3.14159265358979" xyz="0.0472499999999947 -0.0119000000000034 -0.0272499999991938"/>
<parent link="link_arm_l0"/>
<child link="link_aruco_inner_wrist"/>
<axis xyz="0 0 0"/>
</joint>
<material name="aluminum">
<color rgba="0.5 0.5 0.5 1"/>
</material>
<material name="plastic">
<color rgba="0.1 0.1 0.1 1"/>
</material>
<!-- camera body, with origin at bottom screw mount -->
<joint name="camera_joint" type="fixed">
<origin rpy="0.0 0.0 0.0" xyz="0.03 -0.0122 0.0182"/>
<parent link="link_head_tilt"/>
<child link="camera_bottom_screw_frame"/>
</joint>
<link name="camera_bottom_screw_frame"/>
<joint name="camera_link_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.010600000000000002 0.0175 0.0125"/>
<parent link="camera_bottom_screw_frame"/>
<child link="camera_link"/>
</joint>
<link name="camera_link">
<visual>
<!-- the mesh origin is at front plate in between the two infrared camera axes -->
<origin rpy="1.5707963267948966 0 1.5707963267948966" xyz="0.0043 -0.0175 0"/>
<geometry>
<mesh filename="../meshes/realsense2/d435.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 -0.0175 0"/>
<geometry>
<box size="0.02505 0.09 0.025"/>
</geometry>
</collision>
<inertial>
<!-- The following are not reliable values, and should not be used for modeling -->
<mass value="0.072"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.003881243" ixy="0.0" ixz="0.0" iyy="0.000498940" iyz="0.0" izz="0.003879257"/>
</inertial>
</link>
<!-- camera depth joints and links -->
<joint name="camera_depth_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="camera_link"/>
<child link="camera_depth_frame"/>
</joint>
<link name="camera_depth_frame"/>
<joint name="camera_depth_optical_joint" type="fixed">
<origin rpy="-1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0"/>
<parent link="camera_depth_frame"/>
<child link="camera_depth_optical_frame"/>
</joint>
<link name="camera_depth_optical_frame"/>
<!-- camera left IR joints and links -->
<joint name="camera_infra1_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.0 0"/>
<parent link="camera_link"/>
<child link="camera_infra1_frame"/>
</joint>
<link name="camera_infra1_frame"/>
<joint name="camera_infra1_optical_joint" type="fixed">
<origin rpy="-1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0"/>
<parent link="camera_infra1_frame"/>
<child link="camera_infra1_optical_frame"/>
</joint>
<link name="camera_infra1_optical_frame"/>
<!-- camera right IR joints and links -->
<joint name="camera_infra2_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.05 0"/>
<parent link="camera_link"/>
<child link="camera_infra2_frame"/>
</joint>
<link name="camera_infra2_frame"/>
<joint name="camera_infra2_optical_joint" type="fixed">
<origin rpy="-1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0"/>
<parent link="camera_infra2_frame"/>
<child link="camera_infra2_optical_frame"/>
</joint>
<link name="camera_infra2_optical_frame"/>
<!-- camera color joints and links -->
<joint name="camera_color_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.015 0"/>
<parent link="camera_link"/>
<child link="camera_color_frame"/>
</joint>
<link name="camera_color_frame"/>
<joint name="camera_color_optical_joint" type="fixed">
<origin rpy="-1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0"/>
<parent link="camera_color_frame"/>
<child link="camera_color_optical_frame"/>
</joint>
<link name="camera_color_optical_frame"/>
<link name="camera_accel_frame"/>
<link name="camera_accel_optical_frame"/>
<link name="camera_gyro_frame"/>
<link name="camera_gyro_optical_frame"/>
<joint name="camera_accel_joint" type="fixed">
<origin rpy="0 0 0" xyz="-0.01174 -0.00552 0.0051"/>
<parent link="camera_link"/>
<child link="camera_accel_frame"/>
</joint>
<joint name="camera_accel_optical_joint" type="fixed">
<origin rpy="-1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0"/>
<parent link="camera_accel_frame"/>
<child link="camera_accel_optical_frame"/>
</joint>
<joint name="camera_gyro_joint" type="fixed">
<origin rpy="0 0 0" xyz="-0.01174 -0.00552 0.0051"/>
<parent link="camera_link"/>
<child link="camera_gyro_frame"/>
</joint>
<joint name="camera_gyro_optical_joint" type="fixed">
<origin rpy="-1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0"/>
<parent link="camera_gyro_frame"/>
<child link="camera_gyro_optical_frame"/>
</joint>
<link name="laser">
<inertial>
<origin rpy="0 0 0" xyz="0 0 -0.000755956127492408"/>
<mass value="0.0749979022894495"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/laser.obj"/>
</geometry>
<!-- <material name="">
<color rgba="0.250980392156863 0.250980392156863 0.250980392156863 1"/>
</material> -->
</visual>
<collision>
<origin rpy="-1.570796 1.570796 1.570796" xyz="-0.000750 0.000000 0.000000"/>
<geometry>
<box size="0.019500 0.069940 0.069940"/>
</geometry>
</collision>
</link>
<joint name="joint_laser" type="fixed">
<origin rpy="0 0 -3.14159265358979" xyz="0.000502800000000914 0 0.1664"/>
<parent link="base_link"/>
<child link="laser"/>
<axis xyz="0 0 0"/>
</joint>
<link name="respeaker_base">
<inertial>
<origin rpy="0 0 0" xyz="-0.00078082896792734 0.00765742173486017 -0.0042488298301937"/>
<mass value="0.00969129410417277"/>
<inertia ixx="8.95656300428405E-07" ixy="2.67330745809535E-08" ixz="-3.84519793580934E-08" iyy="4.0421099617056E-07" iyz="3.15533542838673E-07" izz="7.08282597118018E-07"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_respeaker.obj"/>
</geometry>
<!-- <material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/>
</material> -->
</visual>
<!--collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/link_respeaker.STL"/>
</geometry>
</collision-->
<collision>
<origin rpy="0.290120 1.487727 1.744709" xyz="-0.000138 0.006371 -0.017378"/>
<geometry>
<box size="0.042669 0.070906 0.079812"/>
</geometry>
</collision>
</link>
<joint name="joint_respeaker" type="fixed">
<!-- rpy=" ? rotate_sound_source_direction ? " -->
<origin rpy="1.57079632679553 0.0 3.14159265358916" xyz="1.09074743137871E-05 1.36992 0.00303572796911382"/>
<parent link="link_mast"/>
<child link="respeaker_base"/>
<axis xyz="0 0 0"/>
</joint>
</robot>