Skip to content
Snippets Groups Projects
ur10_robot.urdf 9.4 KiB
Newer Older
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- |    This document was autogenerated by xacro from ur10_robot.urdf.xacro          | -->
<!-- |    EDITING THIS FILE BY HAND IS NOT RECOMMENDED                                 | -->
<!-- =================================================================================== -->
<robot name="ur10" xmlns:xacro="http://www.ros.org/wiki/xacro">
  <!-- common stuff -->
  <gazebo>
ipa-fxm's avatar
ipa-fxm committed
    <plugin filename="libgazebo_ros_control.so" name="ros_control">
      <!--robotNamespace>/</robotNamespace-->
      <!--robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType-->
    </plugin>
ipa-fxm's avatar
ipa-fxm committed
    <!--
    <plugin name="gazebo_ros_power_monitor_controller" filename="libgazebo_ros_power_monitor.so">
      <alwaysOn>true</alwaysOn>
      <updateRate>1.0</updateRate>
      <timeout>5</timeout>
      <powerStateTopic>power_state</powerStateTopic>
      <powerStateRate>10.0</powerStateRate>
ipa-fxm's avatar
ipa-fxm committed
      <fullChargeCapacity>87.78</fullChargeCapacity>     
      <dischargeRate>-474</dischargeRate>
      <chargeRate>525</chargeRate>
      <dischargeVoltage>15.52</dischargeVoltage>
      <chargeVoltage>16.41</chargeVoltage>
    </plugin>
ipa-fxm's avatar
ipa-fxm committed
-->
  </gazebo>
  <!-- ur10 -->
  <!-- arm -->
  <link name="base_link">
    <visual>
      <geometry>
ipa-fxm's avatar
ipa-fxm committed
        <mesh filename="package://ur_description/meshes/ur10/visual/Base.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10/collision/base.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="4.0"/>
ipa-fxm's avatar
ipa-fxm committed
      <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
      <inertia ixx="0.0061063308908" ixy="0.0" ixz="0.0" iyy="0.0061063308908" iyz="0.0" izz="0.01125"/>
    </inertial>
  </link>
  <joint name="shoulder_pan_joint" type="revolute">
    <parent link="base_link"/>
    <child link="shoulder_link"/>
    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.1273"/>
ipa-fxm's avatar
ipa-fxm committed
    <axis xyz="0 0 1"/>
    <limit effort="330.0" lower="-6.2831853" upper="6.2831853" velocity="2.16"/>
ipa-fxm's avatar
ipa-fxm committed
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="shoulder_link">
    <visual>
      <geometry>
ipa-fxm's avatar
ipa-fxm committed
        <mesh filename="package://ur_description/meshes/ur10/visual/Shoulder.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10/collision/shoulder.stl"/>
      </geometry>
    </collision>
    <inertial>
ipa-fxm's avatar
ipa-fxm committed
      <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
      <inertia ixx="0.0314743125769" ixy="0.0" ixz="0.0" iyy="0.0314743125769" iyz="0.0" izz="0.021875625"/>
    </inertial>
  </link>
  <joint name="shoulder_lift_joint" type="revolute">
    <parent link="shoulder_link"/>
    <child link="upper_arm_link"/>
    <origin rpy="0.0 1.570796325 0.0" xyz="0.0 0.220941 0.0"/>
ipa-fxm's avatar
ipa-fxm committed
    <axis xyz="0 1 0"/>
    <limit effort="330.0" lower="-6.2831853" upper="6.2831853" velocity="2.16"/>
ipa-fxm's avatar
ipa-fxm committed
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="upper_arm_link">
    <visual>
      <geometry>
ipa-fxm's avatar
ipa-fxm committed
        <mesh filename="package://ur_description/meshes/ur10/visual/UpperArm.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10/collision/upper_arm.stl"/>
      </geometry>
    </collision>
    <inertial>
ipa-fxm's avatar
ipa-fxm committed
      <origin rpy="0 0 0" xyz="0.0 0.0 0.306"/>
      <inertia ixx="0.421753803798" ixy="0.0" ixz="0.0" iyy="0.421753803798" iyz="0.0" izz="0.036365625"/>
    </inertial>
  </link>
  <joint name="elbow_joint" type="revolute">
    <parent link="upper_arm_link"/>
    <child link="forearm_link"/>
    <origin rpy="0.0 0.0 0.0" xyz="0.0 -0.1719 0.612"/>
ipa-fxm's avatar
ipa-fxm committed
    <axis xyz="0 1 0"/>
    <limit effort="150.0" lower="-6.2831853" upper="6.2831853" velocity="3.15"/>
ipa-fxm's avatar
ipa-fxm committed
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="forearm_link">
    <visual>
      <geometry>
ipa-fxm's avatar
ipa-fxm committed
        <mesh filename="package://ur_description/meshes/ur10/visual/Forearm.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10/collision/forearm.stl"/>
      </geometry>
    </collision>
    <inertial>
ipa-fxm's avatar
ipa-fxm committed
      <origin rpy="0 0 0" xyz="0.0 0.0 0.28615"/>
      <inertia ixx="0.111069694097" ixy="0.0" ixz="0.0" iyy="0.111069694097" iyz="0.0" izz="0.010884375"/>
    </inertial>
  </link>
  <joint name="wrist_1_joint" type="revolute">
    <parent link="forearm_link"/>
    <child link="wrist_1_link"/>
    <origin rpy="0.0 1.570796325 0.0" xyz="0.0 0.0 0.5723"/>
ipa-fxm's avatar
ipa-fxm committed
    <axis xyz="0 1 0"/>
    <limit effort="54.0" lower="-6.2831853" upper="6.2831853" velocity="3.2"/>
ipa-fxm's avatar
ipa-fxm committed
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="wrist_1_link">
    <visual>
      <geometry>
ipa-fxm's avatar
ipa-fxm committed
        <mesh filename="package://ur_description/meshes/ur10/visual/Wrist1.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10/collision/wrist_1.stl"/>
      </geometry>
    </collision>
    <inertial>
ipa-fxm's avatar
ipa-fxm committed
      <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
      <inertia ixx="0.0051082479567" ixy="0.0" ixz="0.0" iyy="0.0051082479567" iyz="0.0" izz="0.0055125"/>
    </inertial>
  </link>
  <joint name="wrist_2_joint" type="revolute">
    <parent link="wrist_1_link"/>
    <child link="wrist_2_link"/>
    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.1149 0.0"/>
ipa-fxm's avatar
ipa-fxm committed
    <axis xyz="0 0 1"/>
    <limit effort="54.0" lower="-6.2831853" upper="6.2831853" velocity="3.2"/>
ipa-fxm's avatar
ipa-fxm committed
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="wrist_2_link">
    <visual>
      <geometry>
ipa-fxm's avatar
ipa-fxm committed
        <mesh filename="package://ur_description/meshes/ur10/visual/Wrist2.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10/collision/wrist_2.stl"/>
      </geometry>
    </collision>
    <inertial>
ipa-fxm's avatar
ipa-fxm committed
      <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
      <inertia ixx="0.0051082479567" ixy="0.0" ixz="0.0" iyy="0.0051082479567" iyz="0.0" izz="0.0055125"/>
    </inertial>
  </link>
  <joint name="wrist_3_joint" type="revolute">
    <parent link="wrist_2_link"/>
    <child link="wrist_3_link"/>
    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.1157"/>
ipa-fxm's avatar
ipa-fxm committed
    <axis xyz="0 1 0"/>
    <limit effort="54.0" lower="-6.2831853" upper="6.2831853" velocity="3.2"/>
ipa-fxm's avatar
ipa-fxm committed
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="wrist_3_link">
    <visual>
      <geometry>
ipa-fxm's avatar
ipa-fxm committed
        <mesh filename="package://ur_description/meshes/ur10/visual/Wrist3.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10/collision/wrist_3.stl"/>
      </geometry>
    </collision>
    <inertial>
ipa-fxm's avatar
ipa-fxm committed
      <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
      <inertia ixx="0.000526462289415" ixy="0.0" ixz="0.0" iyy="0.000526462289415" iyz="0.0" izz="0.000568125"/>
    </inertial>
  </link>
  <joint name="ee_fixed_joint" type="fixed">
    <parent link="wrist_3_link"/>
    <child link="ee_link"/>
    <origin rpy="0.0 0.0 1.570796325" xyz="0.0 0.0922 0.0"/>
  </joint>
  <link name="ee_link">
    <collision>
      <geometry>
        <box size="0.01 0.01 0.01"/>
      </geometry>
      <origin rpy="0 0 0" xyz="-0.01 0 0"/>
    </collision>
  </link>
  <transmission name="shoulder_pan_trans">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="shoulder_pan_joint"/>
    <actuator name="shoulder_pan_motor">
      <hardwareInterface>EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <transmission name="shoulder_lift_trans">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="shoulder_lift_joint"/>
    <actuator name="shoulder_lift_motor">
      <hardwareInterface>EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <transmission name="elbow_trans">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="elbow_joint"/>
    <actuator name="elbow_motor">
      <hardwareInterface>EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <transmission name="wrist_1_trans">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="wrist_1_joint"/>
    <actuator name="wrist_1_motor">
      <hardwareInterface>EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <transmission name="wrist_2_trans">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="wrist_2_joint"/>
    <actuator name="wrist_2_motor">
      <hardwareInterface>EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <transmission name="wrist_3_trans">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="wrist_3_joint"/>
    <actuator name="wrist_3_motor">
      <hardwareInterface>EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
ipa-fxm's avatar
ipa-fxm committed
  <link name="world"/>
  <joint name="world_joint" type="fixed">
    <parent link="world"/>
    <child link="base_link"/>
    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
  </joint>
</robot>