Skip to content
Snippets Groups Projects
ur5.urdf.xacro 11.7 KiB
Newer Older
<?xml version="1.0"?>
ipa-fxm's avatar
ipa-fxm committed
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
  <xacro:include filename="$(find ur_description)/urdf/ur5.transmission.xacro" />
  <xacro:include filename="$(find ur_description)/urdf/ur5.gazebo.xacro" />
  <property name="pi" value="3.14159265" />

ipa-fxm's avatar
ipa-fxm committed
  <!-- Inertia parameters -->
  <property name="base_mass" value="4.0" />  <!-- This mass might be incorrect -->
  <property name="shoulder_mass" value="3.7000" />
  <property name="upper_arm_mass" value="8.3930" />
  <property name="forearm_mass" value="2.2750" />
  <property name="wrist_1_mass" value="1.2190" />
  <property name="wrist_2_mass" value="1.2190" />
  <property name="wrist_3_mass" value="0.1879" />

  <property name="shoulder_cog" value="0.0 0.00193 -0.02561" />
  <property name="upper_arm_cog" value="0.0 -0.024201 0.2125" />
  <property name="forearm_cog" value="0.0 0.0265 0.11993" />
  <property name="wrist_1_cog" value="0.0 0.110949 0.01634" />
  <property name="wrist_2_cog" value="0.0 0.0018 0.11099" />
  <property name="wrist_3_cog" value="0.0 0.001159 0.0" />
ipa-fxm's avatar
ipa-fxm committed
  <!-- Kinematic model -->
  <!-- Properties from urcontrol.conf -->
  <!--
    DH for UR5:
    a = [0.00000, -0.42500, -0.39225,  0.00000,  0.00000,  0.0000]
    d = [0.089159,  0.00000,  0.00000,  0.10915,  0.09465,  0.0823]
    alpha = [ 1.570796327, 0, 0, 1.570796327, -1.570796327, 0 ]
    q_home_offset = [0, -1.570796327, 0, -1.570796327, 0, 0]
    joint_direction = [-1, -1, 1, 1, 1, 1]
    mass = [3.7000, 8.3930, 2.2750, 1.2190, 1.2190, 0.1879]
    center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, 0.0265], [0, -0.0018, 0.01634], [0, 0.0018,0.01634], [0, 0, -0.001159] ]
  -->
  <property name="ur5_d1" value="0.089159" />
  <property name="ur5_a2" value="-0.42500" />
  <property name="ur5_a3" value="-0.39225" />
  <property name="ur5_d4" value="0.10915" />
  <property name="ur5_d5" value="0.09465" />
  <property name="ur5_d6" value="0.0823" />
ipa-fxm's avatar
ipa-fxm committed

  <!-- Arbitrary offsets for shoulder/elbow joints -->
  <property name="shoulder_offset" value="0.13585" />  <!-- measured from model -->
  <property name="elbow_offset" value="-0.1197" /> <!-- measured from model -->       
ipa-fxm's avatar
ipa-fxm committed

  <!-- link lengths used in model -->
  <property name="shoulder_height" value="${ur5_d1}" />
ipa-fxm's avatar
ipa-fxm committed
  <property name="upper_arm_length" value="${-ur5_a2}" />
  <property name="forearm_length" value="${-ur5_a3}" />
  <property name="wrist_1_length" value="${ur5_d4 - elbow_offset - shoulder_offset}" />
  <property name="wrist_2_length" value="${ur5_d5}" />
  <property name="wrist_3_length" value="${ur5_d6}" />
  <!--property name="shoulder_height" value="0.089159" /-->  
  <!--property name="shoulder_offset" value="0.13585" /-->  <!-- shoulder_offset - elbow_offset + wrist_1_length = 0.10915 -->
  <!--property name="upper_arm_length" value="0.42500" /-->
  <!--property name="elbow_offset" value="0.1197" /-->       <!-- CAD measured -->
  <!--property name="forearm_length" value="0.39225" /-->
  <!--property name="wrist_1_length" value="0.093" /-->     <!-- CAD measured -->
  <!--property name="wrist_2_length" value="0.09465" /-->   <!-- In CAD this distance is 0.930, but in the spec it is 0.09465 -->
  <!--property name="wrist_3_length" value="0.0823" /-->
Wim Meeussen's avatar
Wim Meeussen committed
  <property name="shoulder_radius" value="0.060" />   <!-- manually measured -->
  <property name="upper_arm_radius" value="0.054" />  <!-- manually measured -->
Wim Meeussen's avatar
Wim Meeussen committed
  <property name="elbow_radius" value="0.060" />      <!-- manually measured -->
  <property name="forearm_radius" value="0.040" />    <!-- manually measured -->
  <property name="wrist_radius" value="0.045" />      <!-- manually measured -->
ipa-fxm's avatar
ipa-fxm committed
  <xacro:macro name="cylinder_inertial" params="radius length mass *origin">
ipa-fxm's avatar
ipa-fxm committed
      <mass value="${mass}" />
      <insert_block name="origin" />
      <inertia ixx="${0.0833333 * mass * (3 * radius * radius + length * length)}" ixy="0.0" ixz="0.0"
        iyy="${0.0833333 * mass * (3 * radius * radius + length * length)}" iyz="0.0"
        izz="${0.5 * mass * radius * radius}" />
ipa-fxm's avatar
ipa-fxm committed
  </xacro:macro>


  <xacro:macro name="ur5_robot" params="prefix joint_limited">

    <link name="${prefix}base_link" >
      <visual>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/visual/Base.dae" />
        </geometry>
      </visual>
      <collision>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/collision/base.stl" />
ipa-fxm's avatar
ipa-fxm committed
        </geometry>
      </collision>
      <xacro:cylinder_inertial radius="0.06" length="0.05" mass="${base_mass}">
        <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
ipa-fxm's avatar
ipa-fxm committed
      </xacro:cylinder_inertial>
    </link>

    <joint name="${prefix}shoulder_pan_joint" type="revolute">
      <parent link="${prefix}base_link" />
      <child link = "${prefix}shoulder_link" />
      <origin xyz="0.0 0.0 ${shoulder_height}" rpy="0.0 0.0 0.0" />
      <axis xyz="0 0 1" />
      <xacro:unless value="${joint_limited}">
        <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="150.0" velocity="3.15"/>
ipa-fxm's avatar
ipa-fxm committed
      </xacro:unless>
      <xacro:if value="${joint_limited}">
        <limit lower="${-pi}" upper="${pi}" effort="150.0" velocity="3.15"/>
ipa-fxm's avatar
ipa-fxm committed
      </xacro:if>
      <dynamics damping="0.0" friction="0.0"/>
    </joint>
    
    <link name="${prefix}shoulder_link">
      <visual>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/visual/Shoulder.dae" />
        </geometry>
      </visual>
      <collision>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/collision/shoulder.stl" />
ipa-fxm's avatar
ipa-fxm committed
        </geometry>
      </collision>
      <xacro:cylinder_inertial radius="0.06" length="0.15" mass="${shoulder_mass}">
        <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
ipa-fxm's avatar
ipa-fxm committed
      </xacro:cylinder_inertial>
    </link>

    <joint name="${prefix}shoulder_lift_joint" type="revolute">
      <parent link="${prefix}shoulder_link" />
      <child link = "${prefix}upper_arm_link" />
      <origin xyz="0.0 ${shoulder_offset} 0.0" rpy="0.0 ${pi / 2.0} 0.0" />    
      <axis xyz="0 1 0" />
      <xacro:unless value="${joint_limited}">
        <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="150.0" velocity="3.15"/>
ipa-fxm's avatar
ipa-fxm committed
      </xacro:unless>
      <xacro:if value="${joint_limited}">
        <limit lower="${-pi}" upper="${pi}" effort="150.0" velocity="3.15"/>
ipa-fxm's avatar
ipa-fxm committed
      </xacro:if>
      <dynamics damping="0.0" friction="0.0"/>
    </joint>

    <link name="${prefix}upper_arm_link">
      <visual>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/visual/UpperArm.dae" />
        </geometry>
      </visual>
      <collision>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/collision/upper_arm.stl" />
ipa-fxm's avatar
ipa-fxm committed
        </geometry>
      </collision>
      <xacro:cylinder_inertial radius="0.06" length="0.56" mass="${upper_arm_mass}">
        <origin xyz="0.0 0.0 0.28" rpy="0 0 0" />
ipa-fxm's avatar
ipa-fxm committed
      </xacro:cylinder_inertial>
    </link>

    <joint name="${prefix}elbow_joint" type="revolute">
      <parent link="${prefix}upper_arm_link" />
      <child link = "${prefix}forearm_link" />
      <origin xyz="0.0 ${elbow_offset} ${upper_arm_length}" rpy="0.0 0.0 0.0" />
ipa-fxm's avatar
ipa-fxm committed
      <axis xyz="0 1 0" />
      <xacro:unless value="${joint_limited}">
        <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="150.0" velocity="3.15"/>
      </xacro:unless>
      <xacro:if value="${joint_limited}">
        <limit lower="${-pi}" upper="${pi}" effort="150.0" velocity="3.15"/>
      </xacro:if>
      <dynamics damping="0.0" friction="0.0"/>
    </joint>

    <link name="${prefix}forearm_link">
      <visual>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/visual/Forearm.dae" />
        </geometry>
      </visual>
      <collision>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/collision/forearm.stl" />
ipa-fxm's avatar
ipa-fxm committed
        </geometry>
      </collision>
      <xacro:cylinder_inertial radius="0.06" length="0.5" mass="${forearm_mass}">
        <origin xyz="0.0 0.0 0.25" rpy="0 0 0" />
ipa-fxm's avatar
ipa-fxm committed
      </xacro:cylinder_inertial>
    </link>

    <joint name="${prefix}wrist_1_joint" type="revolute">
      <parent link="${prefix}forearm_link" />
      <child link = "${prefix}wrist_1_link" />
      <origin xyz="0.0 0.0 ${forearm_length}" rpy="0.0 ${pi / 2.0} 0.0" />
      <axis xyz="0 1 0" />
      <xacro:unless value="${joint_limited}">
        <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="28.0" velocity="3.2"/>
ipa-fxm's avatar
ipa-fxm committed
      </xacro:unless>
      <xacro:if value="${joint_limited}">
        <limit lower="${-pi}" upper="${pi}" effort="28.0" velocity="3.2"/>
ipa-fxm's avatar
ipa-fxm committed
      </xacro:if>
      <dynamics damping="0.0" friction="0.0"/>
    </joint>

    <link name="${prefix}wrist_1_link">
      <visual>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/visual/Wrist1.dae" />
        </geometry>
      </visual>
      <collision>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/collision/wrist_1.stl" />
ipa-fxm's avatar
ipa-fxm committed
        </geometry>
      </collision>
      <xacro:cylinder_inertial radius="0.6" length="0.12" mass="${wrist_1_mass}">
        <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
      </xacro:cylinder_inertial>
ipa-fxm's avatar
ipa-fxm committed
    </link>

    <joint name="${prefix}wrist_2_joint" type="revolute">
      <parent link="${prefix}wrist_1_link" />
      <child link = "${prefix}wrist_2_link" />
      <origin xyz="0.0 ${wrist_1_length} 0.0" rpy="0.0 0.0 0.0" />
      <axis xyz="0 0 1" />
      <xacro:unless value="${joint_limited}">
        <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="28.0" velocity="3.2"/>
ipa-fxm's avatar
ipa-fxm committed
      </xacro:unless>
      <xacro:if value="${joint_limited}">
        <limit lower="${-pi}" upper="${pi}" effort="28.0" velocity="3.2"/>
ipa-fxm's avatar
ipa-fxm committed
      </xacro:if>
      <dynamics damping="0.0" friction="0.0"/>
    </joint>

    <link name="${prefix}wrist_2_link">
      <visual>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/visual/Wrist2.dae" />
        </geometry>
      </visual>
      <collision>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/collision/wrist_2.stl" />
ipa-fxm's avatar
ipa-fxm committed
        </geometry>
      </collision>
      <xacro:cylinder_inertial radius="0.6" length="0.12" mass="${wrist_2_mass}">
ipa-fxm's avatar
ipa-fxm committed
        <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
      </xacro:cylinder_inertial>
    </link>

    <joint name="${prefix}wrist_3_joint" type="revolute">
      <parent link="${prefix}wrist_2_link" />
      <child link = "${prefix}wrist_3_link" />
      <origin xyz="0.0 0.0 ${wrist_2_length}" rpy="0.0 0.0 0.0" />
ipa-fxm's avatar
ipa-fxm committed
      <axis xyz="0 1 0" />
      <xacro:unless value="${joint_limited}">
        <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="28.0" velocity="3.2"/>
ipa-fxm's avatar
ipa-fxm committed
      </xacro:unless>
      <xacro:if value="${joint_limited}">
        <limit lower="${-pi}" upper="${pi}" effort="28.0" velocity="3.2"/>
ipa-fxm's avatar
ipa-fxm committed
      </xacro:if>
      <dynamics damping="0.0" friction="0.0"/>
    </joint>

    <link name="${prefix}wrist_3_link">
      <visual>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/visual/Wrist3.dae" />
        </geometry>
      </visual>
      <collision>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/collision/wrist_3.stl" />
ipa-fxm's avatar
ipa-fxm committed
        </geometry>
      </collision>
      <xacro:cylinder_inertial radius="0.6" length="0.12" mass="${wrist_3_mass}">
ipa-fxm's avatar
ipa-fxm committed
        <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
      </xacro:cylinder_inertial>
    </link>
    
    <joint name="${prefix}ee_fixed_joint" type="fixed">
      <parent link="${prefix}wrist_3_link" />
      <child link = "${prefix}ee_link" />
      <origin xyz="0.0 ${wrist_3_length} 0.0" rpy="0.0 0.0 ${pi/2.0}" />
    </joint>

    <link name="${prefix}ee_link" />

    <xacro:ur5_arm_transmission prefix="${prefix}" />
    <xacro:ur5_arm_gazebo prefix="${prefix}" />
ipa-fxm's avatar
ipa-fxm committed
  </xacro:macro>
Wim Meeussen's avatar
Wim Meeussen committed
</robot>