<?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:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor" xmlns:xacro="http://ros.org/wiki/xacro"> <!-- common stuff --> <!--gazebo> <controller:gazebo_ros_controller_manager name="gazebo_ros_controller_manager" plugin="libgazebo_ros_controller_manager.so"> <alwaysOn>true</alwaysOn> <updateRate>1000.0</updateRate> <interface:audio name="gazebo_ros_controller_manager_dummy_iface"/> </controller:gazebo_ros_controller_manager> <controller:gazebo_ros_power_monitor name="gazebo_ros_power_monitor_controller" plugin="libgazebo_ros_power_monitor.so"> <alwaysOn>true</alwaysOn> <updateRate>1.0</updateRate> <timeout>5</timeout> <interface:audio name="power_monitor_dummy_interface"/> <powerStateTopic>power_state</powerStateTopic> <powerStateRate>10.0</powerStateRate> <fullChargeCapacity>87.78</fullChargeCapacity> <dischargeRate>-474</dischargeRate> <chargeRate>525</chargeRate> <dischargeVoltage>15.52</dischargeVoltage> <chargeVoltage>16.41</chargeVoltage> </controller:gazebo_ros_power_monitor> </gazebo--> <!-- ur5 --> <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/ur5/visual/Base.dae"/> </geometry> <origin rpy="0.0 0.0 2.3561944875" xyz="0.0 0.0 0.003"/> </visual> <collision> <geometry> <mesh filename="package://ur_description/meshes/ur5/collision/Base.dae"/> </geometry> <!-- <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 -0.009159"/> --> </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.089159"/> <axis xyz="0 0 1"/> <limit effort="10.0" lower="-3.14159265" upper="3.14159265" velocity="3.14159265"/> <dynamics damping="10" friction="0.1"/> </joint> <link name="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.dae"/> </geometry> <!-- <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 -0.009159"/> --> </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.13585 0.0"/> <axis xyz="0 1 0"/> <limit effort="10.0" lower="-3.14159265" upper="3.14159265" velocity="3.14159265"/> <dynamics damping="10" friction="0.1"/> </joint> <link name="upper_arm_link"> <visual> <geometry> <mesh filename="package://ur_description/meshes/ur5/visual/UpperArm.dae"/> </geometry> <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/> </visual> <collision> <geometry> <mesh filename="package://ur_description/meshes/ur5/collision/UpperArm.dae"/> </geometry> <!-- <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.2125"/> --> </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.1197 0.425"/> <axis xyz="0 1 0"/> <limit effort="10.0" lower="-3.14159265" upper="3.14159265" velocity="3.14159265"/> <dynamics damping="10" friction="0.1"/> </joint> <link name="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.dae"/> </geometry> <!-- <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.196125"/> --> </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.39225"/> <axis xyz="0 1 0"/> <limit effort="10.0" lower="-3.14159265" upper="0.7853981625" velocity="3.14159265"/> <dynamics damping="10" friction="0.1"/> </joint> <link name="wrist_1_link"> <visual> <geometry> <mesh filename="package://ur_description/meshes/ur5/visual/Wrist1.dae"/> </geometry> <origin rpy="0.0 1.570796325 0.0" xyz="0.0 0.093 0.0"/> </visual> <collision> <geometry> <mesh filename="package://ur_description/meshes/ur5/collision/Wrist1.dae"/> </geometry> <origin rpy="0.0 1.570796325 0.0" xyz="0.0 0.093 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.093 0.0"/> <axis xyz="0 0 1"/> <limit effort="10.0" lower="-3.14159265" upper="3.14159265" velocity="3.14159265"/> <dynamics damping="10" friction="0.1"/> </joint> <link name="wrist_2_link"> <visual> <geometry> <mesh filename="package://ur_description/meshes/ur5/visual/Wrist2.dae"/> </geometry> <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.09465"/> </visual> <collision> <geometry> <mesh filename="package://ur_description/meshes/ur5/collision/Wrist2.dae"/> </geometry> <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.09465"/> </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.09465"/> <axis xyz="0 1 0"/> <limit effort="10.0" lower="-3.14159265" upper="3.14159265" velocity="3.14159265"/> <dynamics damping="10" friction="0.1"/> </joint> <link name="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/Wrist3.dae"/> </geometry> </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.0823 0.0"/> </joint> <link name="ee_link"/> <xacro:ur_arm_transmission name=""/> <!--gazebo reference="universal_robot"> <material>Gazebo/Blue</material> </gazebo--> </robot>