333 lines
12 KiB
Plaintext
333 lines
12 KiB
Plaintext
|
|
<?xml version="1.0" ?>
|
||
|
|
<!-- =================================================================================== -->
|
||
|
|
<!-- | This document was autogenerated by xacro from ur10e_robot.urdf.xacro | -->
|
||
|
|
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
||
|
|
<!-- =================================================================================== -->
|
||
|
|
<robot name="ur10e" xmlns:xacro="http://ros.org/wiki/xacro">
|
||
|
|
<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>
|
||
|
|
<!--
|
||
|
|
Author: Kelsey Hawkins
|
||
|
|
Contributers: Jimmy Da Silva, Ajit Krisshna N L, Muhammad Asif Rana
|
||
|
|
-->
|
||
|
|
<link name="base_link">
|
||
|
|
<visual>
|
||
|
|
<geometry>
|
||
|
|
<mesh filename="package://ur_e_description/meshes/ur10e/visual/base.dae"/>
|
||
|
|
</geometry>
|
||
|
|
<material name="LightGrey">
|
||
|
|
<color rgba="0.7 0.7 0.7 1.0"/>
|
||
|
|
</material>
|
||
|
|
</visual>
|
||
|
|
<collision>
|
||
|
|
<geometry>
|
||
|
|
<mesh filename="package://ur_e_description/meshes/ur10e/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.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.181"/>
|
||
|
|
<axis xyz="0 0 1"/>
|
||
|
|
<limit effort="330.0" lower="-6.28318530718" upper="6.28318530718" velocity="3.14"/>
|
||
|
|
<dynamics damping="0.0" friction="0.0"/>
|
||
|
|
</joint>
|
||
|
|
<link name="shoulder_link">
|
||
|
|
<visual>
|
||
|
|
<geometry>
|
||
|
|
<mesh filename="package://ur_e_description/meshes/ur10e/visual/shoulder.dae"/>
|
||
|
|
</geometry>
|
||
|
|
<material name="LightGrey">
|
||
|
|
<color rgba="0.7 0.7 0.7 1.0"/>
|
||
|
|
</material>
|
||
|
|
</visual>
|
||
|
|
<collision>
|
||
|
|
<geometry>
|
||
|
|
<mesh filename="package://ur_e_description/meshes/ur10e/collision/shoulder.stl"/>
|
||
|
|
</geometry>
|
||
|
|
</collision>
|
||
|
|
<inertial>
|
||
|
|
<mass value="7.778"/>
|
||
|
|
<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.57079632679 0.0" xyz="0.0 0.176 0.0"/>
|
||
|
|
<axis xyz="0 1 0"/>
|
||
|
|
<limit effort="330.0" lower="-6.28318530718" upper="6.28318530718" velocity="3.14"/>
|
||
|
|
<dynamics damping="0.0" friction="0.0"/>
|
||
|
|
</joint>
|
||
|
|
<link name="upper_arm_link">
|
||
|
|
<visual>
|
||
|
|
<geometry>
|
||
|
|
<mesh filename="package://ur_e_description/meshes/ur10e/visual/upperarm.dae"/>
|
||
|
|
</geometry>
|
||
|
|
<material name="LightGrey">
|
||
|
|
<color rgba="0.7 0.7 0.7 1.0"/>
|
||
|
|
</material>
|
||
|
|
</visual>
|
||
|
|
<collision>
|
||
|
|
<geometry>
|
||
|
|
<mesh filename="package://ur_e_description/meshes/ur10e/collision/upperarm.stl"/>
|
||
|
|
</geometry>
|
||
|
|
</collision>
|
||
|
|
<inertial>
|
||
|
|
<mass value="12.93"/>
|
||
|
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.3065"/>
|
||
|
|
<inertia ixx="0.42307374077" ixy="0.0" ixz="0.0" iyy="0.42307374077" 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.137 0.613"/>
|
||
|
|
<axis xyz="0 1 0"/>
|
||
|
|
<limit effort="150.0" lower="-3.14159265359" upper="3.14159265359" velocity="3.14"/>
|
||
|
|
<dynamics damping="0.0" friction="0.0"/>
|
||
|
|
</joint>
|
||
|
|
<link name="forearm_link">
|
||
|
|
<visual>
|
||
|
|
<geometry>
|
||
|
|
<mesh filename="package://ur_e_description/meshes/ur10e/visual/forearm.dae"/>
|
||
|
|
</geometry>
|
||
|
|
<material name="LightGrey">
|
||
|
|
<color rgba="0.7 0.7 0.7 1.0"/>
|
||
|
|
</material>
|
||
|
|
</visual>
|
||
|
|
<collision>
|
||
|
|
<geometry>
|
||
|
|
<mesh filename="package://ur_e_description/meshes/ur10e/collision/forearm.stl"/>
|
||
|
|
</geometry>
|
||
|
|
</collision>
|
||
|
|
<inertial>
|
||
|
|
<mass value="3.87"/>
|
||
|
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.2855"/>
|
||
|
|
<inertia ixx="0.110590365764" ixy="0.0" ixz="0.0" iyy="0.110590365764" 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.57079632679 0.0" xyz="0.0 0.0 0.571"/>
|
||
|
|
<axis xyz="0 1 0"/>
|
||
|
|
<limit effort="54.0" lower="-6.28318530718" upper="6.28318530718" velocity="6.28"/>
|
||
|
|
<dynamics damping="0.0" friction="0.0"/>
|
||
|
|
</joint>
|
||
|
|
<link name="wrist_1_link">
|
||
|
|
<visual>
|
||
|
|
<geometry>
|
||
|
|
<mesh filename="package://ur_e_description/meshes/ur10e/visual/wrist1.dae"/>
|
||
|
|
</geometry>
|
||
|
|
<material name="LightGrey">
|
||
|
|
<color rgba="0.7 0.7 0.7 1.0"/>
|
||
|
|
</material>
|
||
|
|
</visual>
|
||
|
|
<collision>
|
||
|
|
<geometry>
|
||
|
|
<mesh filename="package://ur_e_description/meshes/ur10e/collision/wrist1.stl"/>
|
||
|
|
</geometry>
|
||
|
|
</collision>
|
||
|
|
<inertial>
|
||
|
|
<mass value="1.96"/>
|
||
|
|
<origin rpy="0 0 0" xyz="0.0 0.135 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.135 0.0"/>
|
||
|
|
<axis xyz="0 0 1"/>
|
||
|
|
<limit effort="54.0" lower="-6.28318530718" upper="6.28318530718" velocity="6.28"/>
|
||
|
|
<dynamics damping="0.0" friction="0.0"/>
|
||
|
|
</joint>
|
||
|
|
<link name="wrist_2_link">
|
||
|
|
<visual>
|
||
|
|
<geometry>
|
||
|
|
<mesh filename="package://ur_e_description/meshes/ur10e/visual/wrist2.dae"/>
|
||
|
|
</geometry>
|
||
|
|
<material name="LightGrey">
|
||
|
|
<color rgba="0.7 0.7 0.7 1.0"/>
|
||
|
|
</material>
|
||
|
|
</visual>
|
||
|
|
<collision>
|
||
|
|
<geometry>
|
||
|
|
<mesh filename="package://ur_e_description/meshes/ur10e/collision/wrist2.stl"/>
|
||
|
|
</geometry>
|
||
|
|
</collision>
|
||
|
|
<inertial>
|
||
|
|
<mass value="1.96"/>
|
||
|
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.12"/>
|
||
|
|
<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.12"/>
|
||
|
|
<axis xyz="0 1 0"/>
|
||
|
|
<limit effort="54.0" lower="-6.28318530718" upper="6.28318530718" velocity="6.28"/>
|
||
|
|
<dynamics damping="0.0" friction="0.0"/>
|
||
|
|
</joint>
|
||
|
|
<link name="wrist_3_link">
|
||
|
|
<visual>
|
||
|
|
<geometry>
|
||
|
|
<mesh filename="package://ur_e_description/meshes/ur10e/visual/wrist3.dae"/>
|
||
|
|
</geometry>
|
||
|
|
<material name="LightGrey">
|
||
|
|
<color rgba="0.7 0.7 0.7 1.0"/>
|
||
|
|
</material>
|
||
|
|
</visual>
|
||
|
|
<collision>
|
||
|
|
<geometry>
|
||
|
|
<mesh filename="package://ur_e_description/meshes/ur10e/collision/wrist3.stl"/>
|
||
|
|
</geometry>
|
||
|
|
</collision>
|
||
|
|
<inertial>
|
||
|
|
<mass value="0.202"/>
|
||
|
|
<origin rpy="1.57079632679 0 0" xyz="0.0 0.092 0.0"/>
|
||
|
|
<inertia ixx="0.000144345775595" ixy="0.0" ixz="0.0" iyy="0.000144345775595" iyz="0.0" izz="0.000204525"/>
|
||
|
|
</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.57079632679" xyz="0.0 0.117 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>hardware_interface/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>hardware_interface/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>hardware_interface/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>hardware_interface/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>hardware_interface/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>hardware_interface/PositionJointInterface</hardwareInterface>
|
||
|
|
</joint>
|
||
|
|
<actuator name="wrist_3_motor">
|
||
|
|
<mechanicalReduction>1</mechanicalReduction>
|
||
|
|
</actuator>
|
||
|
|
</transmission>
|
||
|
|
<gazebo reference="shoulder_link">
|
||
|
|
<selfCollide>true</selfCollide>
|
||
|
|
</gazebo>
|
||
|
|
<gazebo reference="upper_arm_link">
|
||
|
|
<selfCollide>true</selfCollide>
|
||
|
|
</gazebo>
|
||
|
|
<gazebo reference="forearm_link">
|
||
|
|
<selfCollide>true</selfCollide>
|
||
|
|
</gazebo>
|
||
|
|
<gazebo reference="wrist_1_link">
|
||
|
|
<selfCollide>true</selfCollide>
|
||
|
|
</gazebo>
|
||
|
|
<gazebo reference="wrist_3_link">
|
||
|
|
<selfCollide>true</selfCollide>
|
||
|
|
</gazebo>
|
||
|
|
<gazebo reference="wrist_2_link">
|
||
|
|
<selfCollide>true</selfCollide>
|
||
|
|
</gazebo>
|
||
|
|
<gazebo reference="ee_link">
|
||
|
|
<selfCollide>true</selfCollide>
|
||
|
|
</gazebo>
|
||
|
|
<!-- ROS base_link to UR 'Base' Coordinates transform -->
|
||
|
|
<link name="base"/>
|
||
|
|
<joint name="base_link-base_fixed_joint" type="fixed">
|
||
|
|
<!-- NOTE: this rotation is only needed as long as base_link itself is
|
||
|
|
not corrected wrt the real robot (ie: rotated over 180
|
||
|
|
degrees)
|
||
|
|
-->
|
||
|
|
<origin rpy="0 0 -3.14159265359" xyz="0 0 0"/>
|
||
|
|
<parent link="base_link"/>
|
||
|
|
<child link="base"/>
|
||
|
|
</joint>
|
||
|
|
<!-- Frame coincident with all-zeros TCP on UR controller -->
|
||
|
|
<link name="tool0"/>
|
||
|
|
<joint name="wrist_3_link-tool0_fixed_joint" type="fixed">
|
||
|
|
<origin rpy="-1.57079632679 0 0" xyz="0 0.117 0"/>
|
||
|
|
<parent link="wrist_3_link"/>
|
||
|
|
<child link="tool0"/>
|
||
|
|
</joint>
|
||
|
|
<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>
|
||
|
|
|