|
|
<?xml version="1.0" encoding="utf-8"?> |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
<robot name="ur5e" xmlns:xacro="http://wiki.ros.org/xacro"> |
|
|
<material name="LightGrey"> |
|
|
<color rgba="0.8 0.8 0.8 1.0"/> |
|
|
</material> |
|
|
<material name="LightBlue"> |
|
|
<color rgba="0.49 0.67 0.8 1.0"/> |
|
|
</material> |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
<link name="base_link"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="visual/base.obj"/> |
|
|
</geometry> |
|
|
<material name="LightGrey"/> |
|
|
</visual> |
|
|
<collision> |
|
|
<geometry> |
|
|
<mesh filename="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.163"/> |
|
|
<axis xyz="0 0 1"/> |
|
|
<limit effort="150.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="3.14"/> |
|
|
<dynamics damping="0.0" friction="0.0"/> |
|
|
</joint> |
|
|
<link name="shoulder_link"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="visual/shoulder.obj"/> |
|
|
</geometry> |
|
|
<material name="LightBlue"/> |
|
|
</visual> |
|
|
<collision> |
|
|
<geometry> |
|
|
<mesh filename="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.5707963267948966 0.0" xyz="0.0 0.138 0.0"/> |
|
|
<axis xyz="0 1 0"/> |
|
|
<limit effort="150.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="3.14"/> |
|
|
<dynamics damping="0.0" friction="0.0"/> |
|
|
</joint> |
|
|
<link name="upper_arm_link"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="visual/upperarm.obj"/> |
|
|
</geometry> |
|
|
<material name="LightGrey"/> |
|
|
</visual> |
|
|
<collision> |
|
|
<geometry> |
|
|
<mesh filename="collision/upperarm.stl"/> |
|
|
</geometry> |
|
|
</collision> |
|
|
<inertial> |
|
|
<mass value="8.393"/> |
|
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.2125"/> |
|
|
<inertia ixx="0.1338857818623325" ixy="0.0" ixz="0.0" iyy="0.1338857818623325" 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.141592653589793" upper="3.141592653589793" velocity="3.14"/> |
|
|
<dynamics damping="0.0" friction="0.0"/> |
|
|
</joint> |
|
|
<link name="forearm_link"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="visual/forearm.obj"/> |
|
|
</geometry> |
|
|
<material name="LightBlue"/> |
|
|
</visual> |
|
|
<collision> |
|
|
<geometry> |
|
|
<mesh filename="collision/forearm.stl"/> |
|
|
</geometry> |
|
|
</collision> |
|
|
<inertial> |
|
|
<mass value="2.275"/> |
|
|
<origin rpy="0 0 0" xyz="0.0 0.0 0.196"/> |
|
|
<inertia ixx="0.031179620861480004" ixy="0.0" ixz="0.0" iyy="0.031179620861480004" 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.5707963267948966 0.0" xyz="0.0 0.0 0.392"/> |
|
|
<axis xyz="0 1 0"/> |
|
|
<limit effort="28.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="6.28"/> |
|
|
<dynamics damping="0.0" friction="0.0"/> |
|
|
</joint> |
|
|
<link name="wrist_1_link"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="visual/wrist1.obj"/> |
|
|
</geometry> |
|
|
<material name="LightGrey"/> |
|
|
</visual> |
|
|
<collision> |
|
|
<geometry> |
|
|
<mesh filename="collision/wrist1.stl"/> |
|
|
</geometry> |
|
|
</collision> |
|
|
<inertial> |
|
|
<mass value="1.219"/> |
|
|
<origin rpy="0 0 0" xyz="0.0 0.127 0.0"/> |
|
|
<inertia ixx="0.0025598989760400002" ixy="0.0" ixz="0.0" iyy="0.0025598989760400002" iyz="0.0" izz="0.0021942"/> |
|
|
</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.283185307179586" upper="6.283185307179586" velocity="6.28"/> |
|
|
<dynamics damping="0.0" friction="0.0"/> |
|
|
</joint> |
|
|
<link name="wrist_2_link"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="visual/wrist2.obj"/> |
|
|
</geometry> |
|
|
<material name="LightBlue"/> |
|
|
</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.1"/> |
|
|
<inertia ixx="0.0025598989760400002" ixy="0.0" ixz="0.0" iyy="0.0025598989760400002" iyz="0.0" izz="0.0021942"/> |
|
|
</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.1"/> |
|
|
<axis xyz="0 1 0"/> |
|
|
<limit effort="28.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="6.28"/> |
|
|
<dynamics damping="0.0" friction="0.0"/> |
|
|
</joint> |
|
|
<link name="wrist_3_link"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="visual/wrist3.obj"/> |
|
|
</geometry> |
|
|
<material name="LightGrey"/> |
|
|
</visual> |
|
|
<collision> |
|
|
<geometry> |
|
|
<mesh filename="collision/wrist3.stl"/> |
|
|
</geometry> |
|
|
</collision> |
|
|
<inertial> |
|
|
<mass value="0.1879"/> |
|
|
<origin rpy="1.5707963267948966 0 0" xyz="0.0 0.0771 0.0"/> |
|
|
<inertia ixx="9.890410052167731e-05" ixy="0.0" ixz="0.0" iyy="9.890410052167731e-05" iyz="0.0" izz="0.0001321171875"/> |
|
|
</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.5707963267948966" xyz="0.0 0.1 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> |
|
|
<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> |
|
|
</robot> |
|
|
|