|
<?xml version="1.0" ?> |
|
|
|
|
|
|
|
|
|
<robot name="ur5" xmlns:xacro="http://ros.org/wiki/xacro"> |
|
<material name="LightGrey"> |
|
<color rgba="0.8 0.8 0.8 1.0"/> |
|
</material> |
|
|
|
<material name="DarkGrey"> |
|
<color rgba="0.2 0.2 0.2 1.0"/> |
|
</material> |
|
|
|
<link name="base_link"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="visual/base.dae"/> |
|
</geometry> |
|
<material name="LightGrey"/> |
|
</visual> |
|
|
|
|
|
|
|
|
|
|
|
<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.163"/> |
|
<axis xyz="0 0 1"/> |
|
<limit effort="150.0" lower="-6.28318530718" upper="6.28318530718" velocity="3.15"/> |
|
<dynamics damping="0.0" friction="0.0"/> |
|
</joint> |
|
<link name="shoulder_link"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="visual/shoulder.dae"/> |
|
</geometry> |
|
<material name="DarkGrey"/> |
|
</visual> |
|
|
|
|
|
|
|
|
|
|
|
<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.57079632679 0.0" xyz="0.0 0.138 0.0"/> |
|
<axis xyz="0 1 0"/> |
|
<limit effort="150.0" lower="-6.28318530718" upper="6.28318530718" velocity="3.15"/> |
|
<dynamics damping="0.0" friction="0.0"/> |
|
</joint> |
|
<link name="upper_arm_link"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="visual/upperarm.dae"/> |
|
</geometry> |
|
<material name="LightGrey"/> |
|
</visual> |
|
|
|
|
|
|
|
|
|
|
|
<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.131 0.425"/> |
|
<axis xyz="0 1 0"/> |
|
<limit effort="150.0" lower="-3.14159265359" upper="3.14159265359" velocity="3.15"/> |
|
<dynamics damping="0.0" friction="0.0"/> |
|
</joint> |
|
<link name="forearm_link"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="visual/forearm.dae"/> |
|
</geometry> |
|
<material name="DarkGrey"/> |
|
</visual> |
|
|
|
|
|
|
|
|
|
|
|
<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.57079632679 0.0" xyz="0.0 0.0 0.392"/> |
|
<axis xyz="0 1 0"/> |
|
<limit effort="28.0" lower="-6.28318530718" upper="6.28318530718" velocity="3.2"/> |
|
<dynamics damping="0.0" friction="0.0"/> |
|
</joint> |
|
<link name="wrist_1_link"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="visual/wrist1.dae"/> |
|
</geometry> |
|
<material name="LightGrey"/> |
|
</visual> |
|
|
|
|
|
|
|
|
|
|
|
<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.127 0.0"/> |
|
<axis xyz="0 0 1"/> |
|
<limit effort="28.0" lower="-6.28318530718" upper="6.28318530718" velocity="3.2"/> |
|
<dynamics damping="0.0" friction="0.0"/> |
|
</joint> |
|
<link name="wrist_2_link"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="visual/wrist2.dae"/> |
|
</geometry> |
|
<material name="DarkGrey"/> |
|
</visual> |
|
<collision> |
|
<geometry> |
|
<mesh filename="collision/wrist2.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.100"/> |
|
<axis xyz="0 1 0"/> |
|
<limit effort="28.0" lower="-6.28318530718" upper="6.28318530718" velocity="3.2"/> |
|
<dynamics damping="0.0" friction="0.0"/> |
|
</joint> |
|
<link name="wrist_3_link"> |
|
<visual> |
|
<geometry> |
|
<mesh filename="visual/wrist3.dae"/> |
|
</geometry> |
|
<material name="LightGrey"/> |
|
</visual> |
|
<collision> |
|
<geometry> |
|
<mesh filename="collision/wrist3.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="-1.5707963267948966 0.0 0.0" xyz="0.0 0.100 0.0"/> |
|
</joint> |
|
<link name="ee_link"> |
|
|
|
|
|
|
|
|
|
|
|
|
|
<inertial> |
|
<mass value="0.0"/> |
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> |
|
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/> |
|
</inertial> |
|
</link> |
|
|
|
|
|
<link name="base"> |
|
<inertial> |
|
<mass value="0.0"/> |
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> |
|
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/> |
|
</inertial> |
|
</link> |
|
<joint name="base_link-base_fixed_joint" type="fixed"> |
|
|
|
|
|
|
|
|
|
<origin rpy="0 0 -3.14159265359" xyz="0 0 0"/> |
|
<parent link="base_link"/> |
|
<child link="base"/> |
|
</joint> |
|
|
|
<link name="tool0"> |
|
<inertial> |
|
<mass value="0.0"/> |
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> |
|
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/> |
|
</inertial> |
|
</link> |
|
<joint name="wrist_3_link-tool0_fixed_joint" type="fixed"> |
|
<origin rpy="-1.57079632679 0 0" xyz="0 0.0823 0"/> |
|
<parent link="wrist_3_link"/> |
|
<child link="tool0"/> |
|
</joint> |
|
|
|
<link name="tool_tip"> |
|
<inertial> |
|
<mass value="0.0"/> |
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> |
|
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/> |
|
</inertial> |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
</link> |
|
<joint name="tool0_fixed_joint-tool_tip" type="fixed"> |
|
<origin rpy="0 0 0" xyz="0 0 0.175"/> |
|
<parent link="tool0"/> |
|
<child link="tool_tip"/> |
|
</joint> |
|
|
|
<link name="world"/> |
|
<joint name="world_joint" type="fixed"> |
|
<parent link="world"/> |
|
<child link="rotated_base_link"/> |
|
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/> |
|
</joint> |
|
|
|
<link name="rotated_base_link"> |
|
<inertial> |
|
<mass value="0.0"/> |
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/> |
|
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/> |
|
</inertial> |
|
</link>> |
|
|
|
<joint name="rotated_base-base_fixed_joint" type="fixed"> |
|
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 3.141592653589793"/> |
|
<parent link="rotated_base_link"/> |
|
<child link="base_link"/> |
|
</joint> |
|
</robot> |
|
|