<?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> <plugin filename="libgazebo_ros_control.so" name="ros_control"> <!--robotNamespace>/</robotNamespace--> <!--robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType--> </plugin> <!-- <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> <fullChargeCapacity>87.78</fullChargeCapacity> <dischargeRate>-474</dischargeRate> <chargeRate>525</chargeRate> <dischargeVoltage>15.52</dischargeVoltage> <chargeVoltage>16.41</chargeVoltage> </plugin> --> </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.dae" scale="0.001 0.001 0.001"/> </geometry> <origin rpy="1.570796325 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/Base.dae" scale="0.001 0.001 0.001"/> </geometry> <origin rpy="1.570796325 0.0 0.0" xyz="0.0 0.0 0.0"/> </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.1273"/> <axis xyz="0.0 0.0 1.0"/> <limit effort="330.0" lower="-6.2831853" upper="6.2831853" velocity="2.16"/> <dynamics damping="10" friction="0.1"/> </joint> <link name="shoulder_link"> <visual> <geometry> <mesh filename="package://ur_description/meshes/ur10/visual/Shoulder.dae" scale="0.001 0.001 0.001"/> </geometry> <origin rpy="1.570796325 0.0 0.0" xyz="0.0 0.0 -0.127"/> <!-- -0.127 ???? --> <material name="UR/Grey"/> </visual> <collision> <geometry> <mesh filename="package://ur_description/meshes/ur10/collision/Shoulder.dae" scale="0.001 0.001 0.001"/> </geometry> <origin rpy="1.570796325 0.0 0.0" xyz="0.0 0.0 -0.127"/> <!-- -0.127 ???? --> </collision> <inertial> <mass value="7.778"/> <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.00008 0.00244 -0.037"/> </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"/> <axis xyz="0.0 1.0 0.0"/> <limit effort="330.0" lower="-6.2831853" upper="6.2831853" velocity="2.16"/> <dynamics damping="10" friction="0.1"/> </joint> <link name="upper_arm_link"> <visual> <geometry> <mesh filename="package://ur_description/meshes/ur10/visual/UpperArm.dae" scale="0.001 0.001 0.001"/> </geometry> <origin rpy="1.570796325 0.0 0.0" xyz="0.0 -0.221 -0.127"/> <!-- new offset--> <material name="UR/Blue"/> </visual> <collision> <geometry> <mesh filename="package://ur_description/meshes/ur10/collision/UpperArm.dae" scale="0.001 0.001 0.001"/> </geometry> <origin rpy="1.570796325 0.0 0.0" xyz="0.0 -0.221 -0.127"/> <!-- new offset--> </collision> <inertial> <mass value="12.93"/> <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.00001 0.15061 0.38757"/> </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"/> <axis xyz="0.0 1.0 0.0"/> <limit effort="150.0" lower="-6.2831853" upper="6.2831853" velocity="3.15"/> <dynamics damping="10" friction="0.1"/> </joint> <link name="forearm_link"> <visual> <geometry> <mesh filename="package://ur_description/meshes/ur10/visual/Forearm.dae" scale="0.001 0.001 0.001"/> </geometry> <origin rpy="1.570796325 0.0 0.0" xyz="0.0 -0.049 -0.739"/> <!-- new offset --> <material name="UR/Grey"/> </visual> <collision> <geometry> <mesh filename="package://ur_description/meshes/ur10/collision/Forearm.dae" scale="0.001 0.001 0.001"/> </geometry> <origin rpy="1.570796325 0.0 0.0" xyz="0.0 -0.049 -0.739"/> <!-- new offset --> </collision> <inertial> <mass value="3.87"/> <origin rpy="0.0 0.0 0.0" xyz="-0.00012 0.06112 0.1984"/> <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.5723"/> <axis xyz="0.0 1.0 0.0"/> <limit effort="54.0" lower="-6.2831853" upper="6.2831853" velocity="3.2"/> <dynamics damping="10" friction="0.1"/> </joint> <link name="wrist_1_link"> <visual> <geometry> <mesh filename="package://ur_description/meshes/ur10/visual/Wrist1.dae" scale="0.001 0.001 0.001"/> </geometry> <origin rpy="1.570796325 0 0.0" xyz="0.0 -0.049 -1.312"/> <!-- new offset --> <material name="UR/Blue"/> </visual> <collision> <geometry> <mesh filename="package://ur_description/meshes/ur10/collision/Wrist1.dae" scale="0.001 0.001 0.001"/> </geometry> <origin rpy="1.570796325 0 0.0" xyz="0.0 -0.049 -1.312"/> <!-- new offset --> </collision> <inertial> <mass value="1.96"/> <origin rpy="0.0 0.0 0.0" xyz="-0.00021 -0.00112 0.02269"/> <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.1149 0.0"/> <axis xyz="0.0 0.0 1.0"/> <limit effort="54.0" lower="-6.2831853" upper="6.2831853" velocity="3.2"/> <dynamics damping="10" friction="0.1"/> </joint> <link name="wrist_2_link"> <visual> <geometry> <mesh filename="package://ur_description/meshes/ur10/visual/Wrist2.dae" scale="0.001 0.001 0.001"/> </geometry> <origin rpy="1.570796325 0.0 0.0" xyz="0.0 -0.164 -1.312"/> <!-- new offset --> <material name="UR/Grey"/> </visual> <collision> <geometry> <mesh filename="package://ur_description/meshes/ur10/collision/Wrist2.dae" scale="0.001 0.001 0.001"/> </geometry> <origin rpy="1.570796325 0.0 0.0" xyz="0.0 -0.164 -1.312"/> <!-- new offset --> </collision> <inertial> <mass value="1.96"/> <origin rpy="0.0 0.0 0.0" xyz="-0.00021 0.00112 0.002269"/> <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.1157"/> <axis xyz="0.0 1.0 0.0"/> <limit effort="54.0" lower="-6.2831853" upper="6.2831853" velocity="3.2"/> <dynamics damping="10" friction="0.1"/> </joint> <link name="wrist_3_link"> <visual> <geometry> <mesh filename="package://ur_description/meshes/ur10/visual/Wrist3.dae" scale="0.001 0.001 0.001"/> </geometry> <origin rpy="1.570796325 0.0 0" xyz="0.0 -0.164 -1.427"/> <!-- new offset --> <material name="UR/Blue"/> </visual> <collision> <geometry> <mesh filename="package://ur_description/meshes/ur10/collision/Wrist3.dae" scale="0.001 0.001 0.001"/> </geometry> <origin rpy="1.570796325 0.0 0" xyz="0.0 -0.164 -1.427"/> <!-- new offset --> </collision> <inertial> <mass value="0.202"/> <origin rpy="0.0 0.0 0.0" xyz="0 -0.001156 -0.00149"/> <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.0922 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> <!-- grounding link (needed for MoveIt! compatability --> <link name="world"> </link> <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>