Skip to content
Snippets Groups Projects
ur10_joint_limited_robot.urdf 10.8 KiB
Newer Older
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- |    This document was autogenerated by xacro from ur10_joint_limited_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 -->
  <material name="UR/Blue">
    <color rgba="0.0 0.0 0.8 1.0"/>
  </material>
  <material name="UR/Grey">
    <color rgba="0.7 0.7 0.7 1.0"/>
  </material>
  <!-- arm -->
  <link name="base_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10/visual/Base.stl"/>
      </geometry>
      <origin rpy="0.0 0.0 2.3561944875" xyz="0.0 0.0 0.003"/>
      <material name="UR/Blue"/>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10/collision/Base.stl"/>
      </geometry>
      <origin rpy="0.0 0.0 2.3561944875" xyz="0.0 0.0 0.003"/>
    </collision>
    <inertial>
      <mass value="4.0"/>
      <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
    </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.128"/>
    <axis xyz="0.0 0.0 1.0"/>
    <limit effort="330.0" lower="-3.14159265" upper="3.14159265" velocity="2.16"/>
    <dynamics damping="1.2" friction="0.0"/>
  </joint>
  <link name="shoulder_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10/visual/Shoulder.stl"/>
      </geometry>
      <material name="UR/Grey"/>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10/collision/Shoulder.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="3.7"/>
      <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
      <origin rpy="0.0 0.0 0.0" xyz="0.0 0.00193 -0.02561"/>
    </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.1704 0.0"/>
    <axis xyz="0.0 1.0 0.0"/>
    <limit effort="10.0" lower="-3.14159265" upper="3.14159265" velocity="3.14159265"/>
    <dynamics damping="1.2" friction="0.0"/>
  </joint>
  <link name="upper_arm_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10/visual/UpperArm.stl"/>
      </geometry>
      <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
      <material name="UR/Blue"/>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10/collision/UpperArm.stl"/>
      </geometry>
      <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
    </collision>
    <inertial>
      <mass value="8.393"/>
      <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
      <origin rpy="0.0 0.0 0.0" xyz="0.0 -0.024201 0.2125"/>
    </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.12817 0.60186"/>
    <axis xyz="0.0 1.0 0.0"/>
    <limit effort="150.0" lower="-3.14159265" upper="3.14159265" velocity="3.14159265"/>
    <dynamics damping="0.6" friction="0.0"/>
  </joint>
  <link name="forearm_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10/visual/Forearm.stl"/>
      </geometry>
      <material name="UR/Grey"/>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10/collision/Forearm.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="2.275"/>
      <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0265 0.11993"/>
      <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
    </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.56415"/>
    <axis xyz="0.0 1.0 0.0"/>
    <limit effort="54.0" lower="-3.14159265" upper="3.14159265" velocity="3.14159265"/>
    <dynamics damping="0.6" friction="0.0"/>
  </joint>
  <link name="wrist_1_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10/visual/Wrist1.stl"/>
      </geometry>
      <origin rpy="0.0 0 0.0" xyz="0.0 0.11279 0.0"/>
      <material name="UR/Blue"/>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10/collision/Wrist1.stl"/>
      </geometry>
      <origin rpy="0.0 0 0.0" xyz="0.0 0.11279 0.0"/>
    </collision>
    <inertial>
      <mass value="1.219"/>
      <origin rpy="0.0 0.0 0.0" xyz="0.0 0.110949 0.01634"/>
      <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
    </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.11279 0.0"/>
    <axis xyz="0.0 0.0 1.0"/>
    <limit effort="54.0" lower="-3.14159265" upper="3.14159265" velocity="3.14159265"/>
    <dynamics damping="0.6" friction="0.0"/>
  </joint>
  <link name="wrist_2_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10/visual/Wrist2.stl"/>
      </geometry>
      <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.11279"/>
      <material name="UR/Grey"/>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10/collision/Wrist2.stl"/>
      </geometry>
      <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.11279"/>
    </collision>
    <inertial>
      <mass value="1.219"/>
      <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0018 0.11099"/>
      <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
    </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.11279"/>
    <axis xyz="0.0 1.0 0.0"/>
    <limit effort="54.0" lower="-3.14159265" upper="3.14159265" velocity="3.14159265"/>
    <dynamics damping="0.6" friction="0.0"/>
  </joint>
  <link name="wrist_3_link">
    <visual>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10/visual/Wrist3.stl"/>
      </geometry>
      <origin rpy="0.0 0.0 0" xyz="0.0 0.0857 0.0"/>
      <material name="UR/Blue"/>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur10/collision/Wrist3.stl"/>
      </geometry>
      <origin rpy="0.0 0.0 0" xyz="0.0 0.0857 0.0"/>
    </collision>
    <inertial>
      <mass value="0.1879"/>
      <origin rpy="0.0 0.0 0.0" xyz="0.0 0.001159 0.0"/>
      <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
    </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.0857 0.0"/>
  </joint>
  <link name="ee_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>
  <gazebo reference="base_link">
    <material value="Gazebo/Grey"/>
    <turnGravityOff>false</turnGravityOff>
  </gazebo>
  <gazebo reference="shoulder_pan_link">
    <material value="Gazebo/Blue "/>
    <turnGravityOff>false</turnGravityOff>
  </gazebo>
  <gazebo reference="shoulder_lift_link">
    <material value="Gazebo/Grey"/>
    <turnGravityOff>false</turnGravityOff>
  </gazebo>
  <gazebo reference="elbow_link">
    <material value="Gazebo/Blue "/>
    <turnGravityOff>false</turnGravityOff>
  </gazebo>
  <gazebo reference="wrist_1_link">
    <material value="Gazebo/Grey"/>
    <turnGravityOff>false</turnGravityOff>
  </gazebo>
  <gazebo reference="wrist_2_link">
    <material value="Gazebo/Blue "/>
    <turnGravityOff>false</turnGravityOff>
  </gazebo>
  <gazebo reference="wrist_3_link">
    <material value="Gazebo/Grey"/>
    <turnGravityOff>false</turnGravityOff>
  </gazebo>
</robot>