-
Notifications
You must be signed in to change notification settings - Fork 154
/
irb2400_12_155_macro.xacro
225 lines (222 loc) · 7.92 KB
/
irb2400_12_155_macro.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
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find abb_resources)/urdf/common_materials.xacro"/>
<xacro:macro name="abb_irb2400_12_155" params="prefix">
<!-- link list -->
<link name="${prefix}base_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://abb_irb2400_support/meshes/irb2400_common/visual/base_link.dae"/>
</geometry>
<xacro:material_abb_orange />
</visual>
<collision>
<geometry>
<mesh filename="package://abb_irb2400_support/meshes/irb2400_common/collision/base_link.stl"/>
</geometry>
<xacro:material_abb_yellow />
</collision>
</link>
<link name="${prefix}link_1">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://abb_irb2400_support/meshes/irb2400_common/visual/link_1.dae"/>
</geometry>
<xacro:material_abb_orange />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://abb_irb2400_support/meshes/irb2400_common/collision/link_1.stl"/>
</geometry>
<xacro:material_abb_yellow />
</collision>
</link>
<link name="${prefix}link_2">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://abb_irb2400_support/meshes/irb2400_common/visual/link_2.dae"/>
</geometry>
<xacro:material_abb_orange />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://abb_irb2400_support/meshes/irb2400_common/collision/link_2.stl"/>
</geometry>
<xacro:material_abb_yellow />
</collision>
</link>
<link name="${prefix}link_3">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://abb_irb2400_support/meshes/irb2400_common/visual/link_3.dae"/>
</geometry>
<xacro:material_abb_orange />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://abb_irb2400_support/meshes/irb2400_common/collision/link_3.stl"/>
</geometry>
<xacro:material_abb_yellow />
</collision>
</link>
<link name="${prefix}link_4">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://abb_irb2400_support/meshes/irb2400_common/visual/link_4.dae"/>
</geometry>
<xacro:material_abb_orange />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://abb_irb2400_support/meshes/irb2400_common/collision/link_4.stl"/>
</geometry>
<xacro:material_abb_yellow />
</collision>
</link>
<link name="${prefix}link_5">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://abb_irb2400_support/meshes/irb2400_common/visual/link_5.dae"/>
</geometry>
<xacro:material_abb_orange />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://abb_irb2400_support/meshes/irb2400_common/collision/link_5.stl"/>
</geometry>
<xacro:material_abb_yellow />
</collision>
</link>
<link name="${prefix}link_6">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://abb_irb2400_support/meshes/irb2400_common/visual/link_6.dae"/>
</geometry>
<xacro:material_abb_black />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://abb_irb2400_support/meshes/irb2400_common/collision/link_6.stl"/>
</geometry>
<xacro:material_abb_yellow />
</collision>
</link>
<link name="${prefix}link_lever_a">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://abb_irb2400_support/meshes/irb2400_common/visual/link_lever_a.dae"/>
</geometry>
<xacro:material_abb_black />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://abb_irb2400_support/meshes/irb2400_common/collision/link_lever_a.stl"/>
</geometry>
<xacro:material_abb_yellow />
</collision>
</link>
<link name="${prefix}link_lever_b">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://abb_irb2400_support/meshes/irb2400_common/visual/link_lever_b.dae"/>
</geometry>
<xacro:material_abb_black />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://abb_irb2400_support/meshes/irb2400_common/collision/link_lever_b.stl"/>
</geometry>
<xacro:material_abb_yellow />
</collision>
</link>
<link name="${prefix}tool0"/>
<!-- end of link list -->
<!-- joint list -->
<joint name="${prefix}joint_1" type="revolute">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="${prefix}base_link"/>
<child link="${prefix}link_1"/>
<axis xyz="0 0 1"/>
<limit lower="-3.1416" upper="3.1416" effort="0" velocity="2.618"/>
</joint>
<joint name="${prefix}joint_2" type="revolute">
<origin xyz="0.1 0 0.615" rpy="0 0 0"/>
<parent link="${prefix}link_1"/>
<child link="${prefix}link_2"/>
<axis xyz="0 1 0"/>
<limit lower="-1.7453" upper="1.9199" effort="0" velocity="2.618"/>
</joint>
<joint name="${prefix}joint_3" type="revolute">
<origin xyz="0 0 0.705" rpy="0 0 0"/>
<parent link="${prefix}link_2"/>
<child link="${prefix}link_3"/>
<axis xyz="0 1 0"/>
<limit lower="-1.0472" upper="1.1345" effort="0" velocity="2.618"/>
</joint>
<joint name="${prefix}joint_4" type="revolute">
<origin xyz="0 0 0.135" rpy="0 0 0"/>
<parent link="${prefix}link_3"/>
<child link="${prefix}link_4"/>
<axis xyz="1 0 0"/>
<limit lower="-3.49" upper="3.49" effort="0" velocity="6.2832"/>
</joint>
<joint name="${prefix}joint_5" type="revolute">
<origin xyz="0.755 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_4"/>
<child link="${prefix}link_5"/>
<axis xyz="0 1 0"/>
<limit lower="-2.0944" upper="2.0944" effort="0" velocity="6.2832"/>
</joint>
<joint name="${prefix}joint_6" type="revolute">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_5"/>
<child link="${prefix}link_6"/>
<axis xyz="1 0 0"/>
<limit lower="-6.9813" upper="6.9813" effort="0" velocity="7.854"/>
</joint>
<joint name="${prefix}joint_lever_a" type="continuous">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_2"/>
<child link="${prefix}link_lever_a"/>
<axis xyz="0 1 0"/>
<mimic joint="${prefix}joint_3" multiplier="1.0"/>
</joint>
<joint name="${prefix}joint_lever_b" type="continuous">
<origin xyz="-0.18 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_3"/>
<child link="${prefix}link_lever_b"/>
<axis xyz="0 1 0"/>
<mimic joint="${prefix}joint_3" multiplier="-1.0"/>
</joint>
<joint name="${prefix}joint_6-tool0" type="fixed">
<parent link="${prefix}link_6"/>
<child link="${prefix}tool0"/>
<origin xyz="0.085 0 0" rpy="0 1.57079632679 0"/>
</joint>
<!-- end of joint list -->
<!-- ROS base_link to ABB World Coordinates transform -->
<link name="${prefix}base" />
<joint name="${prefix}base_link-base" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="${prefix}base_link"/>
<child link="${prefix}base"/>
</joint>
</xacro:macro>
</robot>