Newer
Older
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from ur5_robot.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="ur5" xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- common stuff -->
<gazebo>
<plugin filename="libgazebo_ros_control.so" name="ros_control">
<!--robotNamespace>/</robotNamespace-->
<!--robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType-->
<!--
<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>
<dischargeRate>-474</dischargeRate>
<chargeRate>525</chargeRate>
<dischargeVoltage>15.52</dischargeVoltage>
<chargeVoltage>16.41</chargeVoltage>
</plugin>
</gazebo>
<!-- ur5 -->
<!-- arm -->
<link name="base_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur5/visual/Base.dae"/>
</geometry>
<material name="LightGrey">
<color rgba="0.7 0.7 0.7 1.0"/>
</material>
<mesh filename="package://ur_description/meshes/ur5/collision/base.stl"/>
</geometry>
</collision>
<inertial>
<mass value="4.0"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<inertia ixx="0.00443333156" ixy="0.0" ixz="0.0" iyy="0.00443333156" iyz="0.0" izz="0.0072"/>
</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.089159"/>
<axis xyz="0 0 1"/>
<limit effort="150.0" lower="-6.2831853" upper="6.2831853" velocity="3.15"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="shoulder_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur5/visual/Shoulder.dae"/>
</geometry>
<material name="LightGrey">
<color rgba="0.7 0.7 0.7 1.0"/>
</material>
<mesh filename="package://ur_description/meshes/ur5/collision/shoulder.stl"/>
</geometry>
</collision>
<inertial>
<mass value="3.7"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<inertia ixx="0.010267495893" ixy="0.0" ixz="0.0" iyy="0.010267495893" iyz="0.0" izz="0.00666"/>
</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.13585 0.0"/>
<axis xyz="0 1 0"/>
<limit effort="150.0" lower="-6.2831853" upper="6.2831853" velocity="3.15"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="upper_arm_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur5/visual/UpperArm.dae"/>
</geometry>
<material name="LightGrey">
<color rgba="0.7 0.7 0.7 1.0"/>
</material>
<mesh filename="package://ur_description/meshes/ur5/collision/upper_arm.stl"/>
</geometry>
</collision>
<inertial>
<mass value="8.393"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.28"/>
<inertia ixx="0.22689067591" ixy="0.0" ixz="0.0" iyy="0.22689067591" iyz="0.0" izz="0.0151074"/>
</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.1197 0.425"/>
<axis xyz="0 1 0"/>
<limit effort="150.0" lower="-6.2831853" upper="6.2831853" velocity="3.15"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="forearm_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur5/visual/Forearm.dae"/>
</geometry>
<material name="LightGrey">
<color rgba="0.7 0.7 0.7 1.0"/>
</material>
<mesh filename="package://ur_description/meshes/ur5/collision/forearm.stl"/>
</geometry>
</collision>
<inertial>
<mass value="2.275"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.25"/>
<inertia ixx="0.049443313556" ixy="0.0" ixz="0.0" iyy="0.049443313556" iyz="0.0" izz="0.004095"/>
</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.39225"/>
<axis xyz="0 1 0"/>
<limit effort="28.0" lower="-6.2831853" upper="6.2831853" velocity="3.2"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="wrist_1_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur5/visual/Wrist1.dae"/>
</geometry>
<material name="LightGrey">
<color rgba="0.7 0.7 0.7 1.0"/>
</material>
<mesh filename="package://ur_description/meshes/ur5/collision/wrist_1.stl"/>
</geometry>
</collision>
<inertial>
<mass value="1.219"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<inertia ixx="0.111172755531" ixy="0.0" ixz="0.0" iyy="0.111172755531" iyz="0.0" izz="0.21942"/>
</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.093 0.0"/>
<axis xyz="0 0 1"/>
<limit effort="28.0" lower="-6.2831853" upper="6.2831853" velocity="3.2"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="wrist_2_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur5/visual/Wrist2.dae"/>
</geometry>
<material name="LightGrey">
<color rgba="0.7 0.7 0.7 1.0"/>
</material>
<mesh filename="package://ur_description/meshes/ur5/collision/wrist_2.stl"/>
</geometry>
</collision>
<inertial>
<mass value="1.219"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<inertia ixx="0.111172755531" ixy="0.0" ixz="0.0" iyy="0.111172755531" iyz="0.0" izz="0.21942"/>
</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.09465"/>
<axis xyz="0 1 0"/>
<limit effort="28.0" lower="-6.2831853" upper="6.2831853" velocity="3.2"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="wrist_3_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur5/visual/Wrist3.dae"/>
</geometry>
<material name="LightGrey">
<color rgba="0.7 0.7 0.7 1.0"/>
</material>
<mesh filename="package://ur_description/meshes/ur5/collision/wrist_3.stl"/>
</geometry>
</collision>
<inertial>
<mass value="0.1879"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<inertia ixx="0.0171364731454" ixy="0.0" ixz="0.0" iyy="0.0171364731454" iyz="0.0" izz="0.033822"/>
</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.0823 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">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="shoulder_pan_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="shoulder_lift_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="shoulder_lift_joint">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="shoulder_lift_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="elbow_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="elbow_joint">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="elbow_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="wrist_1_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="wrist_1_joint">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="wrist_1_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="wrist_2_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="wrist_2_joint">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="wrist_2_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="wrist_3_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="wrist_3_joint">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="wrist_3_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<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>