-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathdual_arm.xacro
187 lines (152 loc) · 6.63 KB
/
dual_arm.xacro
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
<?xml version="1.0"?>
<robot name="dual_arm" xmlns:xacro="http://ros.org/wiki/xacro">
<!-- add arms names prefixes -->
<xacro:arg name="arm_id_1" default="right_" />
<xacro:arg name="arm_id_2" default="left_" />
<!-- add gripper names prefixes -->
<xacro:include filename="$(find ur_description)/urdf/inc/ur5e_macro.xacro"/>
<link name="world"/>
<!-- wall behind robots -->
<link name="base">
<visual>
<!-- y is half the y dimension of the box, plus 0.508 -->
<!-- z is half the z dimension of the box, plus 0.356 -->
<origin xyz="0 0.608 1.356" rpy="0 0 0" />
<!-- <origin xyz="1.34724341 0.01972794 0.66630936" rpy="1.56466 -8.63678e-05 1.57138" /> -->
<geometry>
<box size="2 0.2 2" />
</geometry>
<material name="White">
<color rgba="1.0 1.0 1.0 1.0" />
</material>
</visual>
<collision>
<origin xyz="0 0.608 1.356" rpy="0 0 0" />
<!-- <origin xyz="1.34724341 0.01972794 0.66630936" rpy="1.56466 -8.63678e-05 1.57138" /> -->
<geometry>
<box size="2 0.2 2" />
</geometry>
</collision>
<inertial>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<mass value="10.0"/>
<inertia ixx="0.001" ixy="0.0" ixz="0.001" iyy="0.0" iyz="0.0" izz="0.001"/>
</inertial>
</link>
<!-- table -->
<link name="table">
<visual>
<origin xyz="0 0 1.22" rpy="0 0 0" />
<geometry>
<box size="1.82 0.76 0.032" />
</geometry>
<material name="White">
<color rgba="1.0 1.0 1.0 1.0" />
</material>
</visual>
<collision>
<origin xyz="0 0 1.22" rpy="0 0 0" />
<geometry>
<box size="1.82 0.76 0.032" />
</geometry>
</collision>
<inertial>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<mass value="10.0"/>
<inertia ixx="0.001" ixy="0.0" ixz="0.001" iyy="0.0" iyz="0.0" izz="0.001"/>
</inertial>
</link>
<joint name="base_to_world" type="fixed">
<parent link="world"/>
<child link="base"/>
<!-- <origin xyz="0.58911788 1.30589175 0.01335737" rpy="0.09474559577728693 -1.5646323542124896 -1.6656300811826108" /> -->
<origin xyz="-0.05011849 -0.00497215 0.01868442" rpy="-1.56466 8.63678e-05 -1.57138" />
<!-- <origin xyz="1.34724341 0.01972794 0.66630936" rpy="1.56466 -8.63678e-05 1.57138" /> -->
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</joint>
<joint name="table_to_world" type="fixed">
<parent link="world"/>
<child link="table"/>
<!-- <origin xyz="0.58911788 1.30589175 0.01335737" rpy="0.09474559577728693 -1.5646323542124896 -1.6656300811826108" /> -->
<origin xyz="0.02 -0.00497215 0.01868442" rpy="-1.56466 8.63678e-05 -1.57138" />
<!-- <origin xyz="1.34724341 0.01972794 0.66630936" rpy="1.56466 -8.63678e-05 1.57138" /> -->
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</joint>
<!-- right arm with gripper -->
<!-- <xacro:ur5e_robot prefix="$(arg arm_id_1)" joint_limits_parameters_file="$(find dual_arm)/scripts/right_joint_limits.yaml"/> -->
<!-- <xacro:ur5e_robot prefix="$(arg arm_id_2)" joint_limits_parameters_file="$(find dual_arm)/scripts/left_joint_limits.yaml"/> -->
<joint name="$(arg arm_id_1)robot_to_base" type="fixed">
<parent link="base"/>
<child link="$(arg arm_id_1)base_link"/>
<!-- <origin xyz="0.432 0.508 0.660" rpy="1.5708 1.5708 0.0"/> -->
<origin xyz="0.311 0.50284408 0.64784629" rpy="2.208204442577555 1.5612544500525112 0.6223073791846901"/>
</joint>
<joint name="$(arg arm_id_2)robot_to_base" type="fixed">
<parent link="base"/>
<child link="$(arg arm_id_2)base_link"/>
<origin xyz="-0.432 0.508 0.660" rpy="1.5708 -1.5708 0.0"/>
</joint>
<xacro:include filename="$(find robotiq_description)/urdf/robotiq_85_gripper.urdf.xacro" />
<!-- Robotiq Coupler -->
<!-- + Height added by the coupler: 8mm -->
<!-- + Reference frame: at the middle (4mm) -->
<link name="$(arg arm_id_1)robotiq_coupler">
<visual>
<geometry>
<mesh filename="package://robotiq_description/meshes/robotiq_85_coupler.stl" />
</geometry>
<!-- <material name="flat_black"/> -->
</visual>
<collision>
<geometry>
<mesh filename="package://robotiq_description/meshes/robotiq_85_coupler.stl" />
</geometry>
</collision>
<inertial>
<origin xyz="2.073e-05 1.45286e-03 -1.1049e-03" rpy="0 0 0" />
<mass value="0.168" />
<inertia ixx="6.69695624e-05" ixy="5.21511788e-09" ixz="-2.74383009e-08"
iyy="7.85088161e-05" iyz="5.41105193e-07" izz="1.41819717e-04"/>
</inertial>
</link>
<joint name="$(arg arm_id_1)robotiq_coupler_joint" type="fixed">
<origin xyz="0 0 0.004" rpy="0 0 ${-pi/2.0}" />
<parent link="$(arg arm_id_1)tool0"/>
<child link="$(arg arm_id_1)robotiq_coupler"/>
</joint>
<!-- Attach the first robotiq 85 gripper -->
<xacro:robotiq_85_gripper prefix="$(arg arm_id_1)" parent="$(arg arm_id_1)robotiq_coupler" >
<origin xyz="0 0 0.004" rpy="0 ${-pi/2} ${pi}"/>
</xacro:robotiq_85_gripper>
<!-- Robotiq Coupler -->
<!-- + Height added by the coupler: 8mm -->
<!-- + Reference frame: at the middle (4mm) -->
<link name="$(arg arm_id_2)robotiq_coupler">
<visual>
<geometry>
<mesh filename="package://robotiq_description/meshes/robotiq_85_coupler.stl" />
</geometry>
<!-- <material name="flat_black"/> -->
</visual>
<collision>
<geometry>
<mesh filename="package://robotiq_description/meshes/robotiq_85_coupler.stl" />
</geometry>
</collision>
<inertial>
<origin xyz="2.073e-05 1.45286e-03 -1.1049e-03" rpy="0 0 0" />
<mass value="0.168" />
<inertia ixx="6.69695624e-05" ixy="5.21511788e-09" ixz="-2.74383009e-08"
iyy="7.85088161e-05" iyz="5.41105193e-07" izz="1.41819717e-04"/>
</inertial>
</link>
<joint name="$(arg arm_id_2)robotiq_coupler_joint" type="fixed">
<origin xyz="0 0 0.004" rpy="0 0 ${-pi/2.0}" />
<parent link="$(arg arm_id_2)tool0"/>
<child link="$(arg arm_id_2)robotiq_coupler"/>
</joint>
<!-- Attach the first robotiq 85 gripper -->
<xacro:robotiq_85_gripper prefix="$(arg arm_id_2)" parent="$(arg arm_id_2)robotiq_coupler" >
<origin xyz="0 0 0.004" rpy="0 ${-pi/2} ${pi}"/>
</xacro:robotiq_85_gripper>
</robot>