Create piper/piper.urdf
Browse files- piper/piper.urdf +568 -0
piper/piper.urdf
ADDED
@@ -0,0 +1,568 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
1 |
+
<?xml version="1.0" encoding="utf-8"?>
|
2 |
+
<robot
|
3 |
+
name="piper_description">
|
4 |
+
<link
|
5 |
+
name="base_link">
|
6 |
+
<!-- <inertial>
|
7 |
+
<origin
|
8 |
+
xyz="-0.00973928490005031 1.8312708928633E-06 0.0410140167677137"
|
9 |
+
rpy="0 0 0" />
|
10 |
+
<mass
|
11 |
+
value="0.162352169522719" />
|
12 |
+
<inertia
|
13 |
+
ixx="0.000226592553127906"
|
14 |
+
ixy="-7.33974356968813E-08"
|
15 |
+
ixz="2.13221970218123E-06"
|
16 |
+
iyy="0.000269447877479622"
|
17 |
+
iyz="8.15167478685076E-09"
|
18 |
+
izz="0.000222318286704" />
|
19 |
+
</inertial> -->
|
20 |
+
<visual>
|
21 |
+
<origin
|
22 |
+
xyz="0 0 0"
|
23 |
+
rpy="0 0 0" />
|
24 |
+
<geometry>
|
25 |
+
<mesh
|
26 |
+
filename="base_link.STL" />
|
27 |
+
</geometry>
|
28 |
+
<material
|
29 |
+
name="">
|
30 |
+
<color
|
31 |
+
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
32 |
+
</material>
|
33 |
+
</visual>
|
34 |
+
<collision>
|
35 |
+
<origin
|
36 |
+
xyz="0 0 0"
|
37 |
+
rpy="0 0 0" />
|
38 |
+
<geometry>
|
39 |
+
<mesh
|
40 |
+
filename="base_link.STL" />
|
41 |
+
</geometry>
|
42 |
+
</collision>
|
43 |
+
</link>
|
44 |
+
<link
|
45 |
+
name="link1">
|
46 |
+
<inertial>
|
47 |
+
<origin
|
48 |
+
xyz="0.00131676031927021 0.000310288842008364 -0.00922874512303438"
|
49 |
+
rpy="0 0 0" />
|
50 |
+
<mass
|
51 |
+
value="0.0978679932242825" />
|
52 |
+
<inertia
|
53 |
+
ixx="7.76684558296781E-05"
|
54 |
+
ixy="1.09084650459916E-07"
|
55 |
+
ixz="-1.97480532432411E-06"
|
56 |
+
iyy="9.24967780161546E-05"
|
57 |
+
iyz="9.91284646834672E-07"
|
58 |
+
izz="8.24589062407806E-05" />
|
59 |
+
</inertial>
|
60 |
+
<visual>
|
61 |
+
<origin
|
62 |
+
xyz="0 0 0"
|
63 |
+
rpy="0 0 0" />
|
64 |
+
<geometry>
|
65 |
+
<mesh
|
66 |
+
filename="link1.STL" />
|
67 |
+
</geometry>
|
68 |
+
<material
|
69 |
+
name="">
|
70 |
+
<color
|
71 |
+
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
72 |
+
</material>
|
73 |
+
</visual>
|
74 |
+
<collision>
|
75 |
+
<origin
|
76 |
+
xyz="0 0 0"
|
77 |
+
rpy="0 0 0" />
|
78 |
+
<geometry>
|
79 |
+
<mesh
|
80 |
+
filename="link1.STL" />
|
81 |
+
</geometry>
|
82 |
+
</collision>
|
83 |
+
</link>
|
84 |
+
<joint
|
85 |
+
name="joint1"
|
86 |
+
type="revolute">
|
87 |
+
<origin
|
88 |
+
xyz="0 0 0.123"
|
89 |
+
rpy="0 0 -1.5708" />
|
90 |
+
<parent
|
91 |
+
link="base_link" />
|
92 |
+
<child
|
93 |
+
link="link1" />
|
94 |
+
<axis
|
95 |
+
xyz="0 0 1" />
|
96 |
+
<limit
|
97 |
+
lower="-2.618"
|
98 |
+
upper="2.618"
|
99 |
+
effort="100"
|
100 |
+
velocity="0" />
|
101 |
+
</joint>
|
102 |
+
<link
|
103 |
+
name="link2">
|
104 |
+
<inertial>
|
105 |
+
<origin
|
106 |
+
xyz="0.147615838821413 -0.0174259998251393 0.00175952516190707"
|
107 |
+
rpy="0 0 0" />
|
108 |
+
<mass
|
109 |
+
value="0.289571136953082" />
|
110 |
+
<inertia
|
111 |
+
ixx="0.000150112628108228"
|
112 |
+
ixy="8.58974959950769E-05"
|
113 |
+
ixz="-1.07428153464285E-06"
|
114 |
+
iyy="0.00172585302855383"
|
115 |
+
iyz="-9.93704792239686E-07"
|
116 |
+
izz="0.00177445942914759" />
|
117 |
+
</inertial>
|
118 |
+
<visual>
|
119 |
+
<origin
|
120 |
+
xyz="0 0 0"
|
121 |
+
rpy="0 0 0" />
|
122 |
+
<geometry>
|
123 |
+
<mesh
|
124 |
+
filename="link2.STL" />
|
125 |
+
</geometry>
|
126 |
+
<material
|
127 |
+
name="">
|
128 |
+
<color
|
129 |
+
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
130 |
+
</material>
|
131 |
+
</visual>
|
132 |
+
<collision>
|
133 |
+
<origin
|
134 |
+
xyz="0 0 0"
|
135 |
+
rpy="0 0 0" />
|
136 |
+
<geometry>
|
137 |
+
<mesh
|
138 |
+
filename="link2.STL" />
|
139 |
+
</geometry>
|
140 |
+
</collision>
|
141 |
+
</link>
|
142 |
+
<joint
|
143 |
+
name="joint2"
|
144 |
+
type="revolute">
|
145 |
+
<origin
|
146 |
+
xyz="0 0 0"
|
147 |
+
rpy="1.5708 -0.10095 -1.5708" />
|
148 |
+
<parent
|
149 |
+
link="link1" />
|
150 |
+
<child
|
151 |
+
link="link2" />
|
152 |
+
<axis
|
153 |
+
xyz="0 0 1" />
|
154 |
+
<limit
|
155 |
+
lower="0"
|
156 |
+
upper="3.14"
|
157 |
+
effort="100"
|
158 |
+
velocity="1" />
|
159 |
+
</joint>
|
160 |
+
<link
|
161 |
+
name="link3">
|
162 |
+
<inertial>
|
163 |
+
<origin
|
164 |
+
xyz="0.0156727246030052 0.104466514905741 0.000508486764144372"
|
165 |
+
rpy="0 0 0" />
|
166 |
+
<mass
|
167 |
+
value="0.290583247455324" />
|
168 |
+
<inertia
|
169 |
+
ixx="0.000221686352136266"
|
170 |
+
ixy="-7.57426543992343E-06"
|
171 |
+
ixz="-6.3700062772173E-07"
|
172 |
+
iyy="0.000100859162015934"
|
173 |
+
iyz="-8.16202696860781E-07"
|
174 |
+
izz="0.000241839316548946" />
|
175 |
+
</inertial>
|
176 |
+
<visual>
|
177 |
+
<origin
|
178 |
+
xyz="0 0 0"
|
179 |
+
rpy="0 0 0" />
|
180 |
+
<geometry>
|
181 |
+
<mesh
|
182 |
+
filename="link3.STL" />
|
183 |
+
</geometry>
|
184 |
+
<material
|
185 |
+
name="">
|
186 |
+
<color
|
187 |
+
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
188 |
+
</material>
|
189 |
+
</visual>
|
190 |
+
<collision>
|
191 |
+
<origin
|
192 |
+
xyz="0 0 0"
|
193 |
+
rpy="0 0 0" />
|
194 |
+
<geometry>
|
195 |
+
<mesh
|
196 |
+
filename="link3.STL" />
|
197 |
+
</geometry>
|
198 |
+
</collision>
|
199 |
+
</link>
|
200 |
+
<joint
|
201 |
+
name="joint3"
|
202 |
+
type="revolute">
|
203 |
+
<origin
|
204 |
+
xyz="0.28503 0 0"
|
205 |
+
rpy="0 0 1.3826" />
|
206 |
+
<parent
|
207 |
+
link="link2" />
|
208 |
+
<child
|
209 |
+
link="link3" />
|
210 |
+
<axis
|
211 |
+
xyz="0 0 1" />
|
212 |
+
<limit
|
213 |
+
lower="-2.967"
|
214 |
+
upper="0"
|
215 |
+
effort="100"
|
216 |
+
velocity="1" />
|
217 |
+
</joint>
|
218 |
+
<link
|
219 |
+
name="link4">
|
220 |
+
<inertial>
|
221 |
+
<origin
|
222 |
+
xyz="0.000276464622388145 -0.00102803669324853 -0.00472830700561612"
|
223 |
+
rpy="0 0 0" />
|
224 |
+
<mass
|
225 |
+
value="0.127087348341362" />
|
226 |
+
<inertia
|
227 |
+
ixx="3.82011730423098E-05"
|
228 |
+
ixy="-4.92358351033589E-08"
|
229 |
+
ixz="4.89589432983109E-08"
|
230 |
+
iyy="4.87048555222491E-05"
|
231 |
+
iyz="6.70802942486707E-08"
|
232 |
+
izz="4.10592077565155E-05" />
|
233 |
+
</inertial>
|
234 |
+
<visual>
|
235 |
+
<origin
|
236 |
+
xyz="0 0 0"
|
237 |
+
rpy="0 0 0" />
|
238 |
+
<geometry>
|
239 |
+
<mesh
|
240 |
+
filename="link4.STL" />
|
241 |
+
</geometry>
|
242 |
+
<material
|
243 |
+
name="">
|
244 |
+
<color
|
245 |
+
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
246 |
+
</material>
|
247 |
+
</visual>
|
248 |
+
<collision>
|
249 |
+
<origin
|
250 |
+
xyz="0 0 0"
|
251 |
+
rpy="0 0 0" />
|
252 |
+
<geometry>
|
253 |
+
<mesh
|
254 |
+
filename="link4.STL" />
|
255 |
+
</geometry>
|
256 |
+
</collision>
|
257 |
+
</link>
|
258 |
+
<joint
|
259 |
+
name="joint4"
|
260 |
+
type="revolute">
|
261 |
+
<origin
|
262 |
+
xyz="0.021984 0.25075 0"
|
263 |
+
rpy="-1.5708 0 0" />
|
264 |
+
<parent
|
265 |
+
link="link3" />
|
266 |
+
<child
|
267 |
+
link="link4" />
|
268 |
+
<axis
|
269 |
+
xyz="0 0 1" />
|
270 |
+
<limit
|
271 |
+
lower="-1.832"
|
272 |
+
upper="1.832"
|
273 |
+
effort="100"
|
274 |
+
velocity="1" />
|
275 |
+
</joint>
|
276 |
+
<link
|
277 |
+
name="link5">
|
278 |
+
<inertial>
|
279 |
+
<origin
|
280 |
+
xyz="8.82261259100015E-05 0.056682908434204 -0.00196119077436732"
|
281 |
+
rpy="0 0 0" />
|
282 |
+
<mass
|
283 |
+
value="0.144711209371719" />
|
284 |
+
<inertia
|
285 |
+
ixx="4.39644269159173E-05"
|
286 |
+
ixy="-3.59214840853815E-08"
|
287 |
+
ixz="-1.89785003257649E-08"
|
288 |
+
iyy="5.63173857792457E-05"
|
289 |
+
iyz="-2.15407623722543E-07"
|
290 |
+
izz="4.88713595021005E-05" />
|
291 |
+
</inertial>
|
292 |
+
<visual>
|
293 |
+
<origin
|
294 |
+
xyz="0 0 0"
|
295 |
+
rpy="0 0 0" />
|
296 |
+
<geometry>
|
297 |
+
<mesh
|
298 |
+
filename="link5.STL" />
|
299 |
+
</geometry>
|
300 |
+
<material
|
301 |
+
name="">
|
302 |
+
<color
|
303 |
+
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
304 |
+
</material>
|
305 |
+
</visual>
|
306 |
+
<collision>
|
307 |
+
<origin
|
308 |
+
xyz="0 0 0"
|
309 |
+
rpy="0 0 0" />
|
310 |
+
<geometry>
|
311 |
+
<mesh
|
312 |
+
filename="link5.STL" />
|
313 |
+
</geometry>
|
314 |
+
</collision>
|
315 |
+
</link>
|
316 |
+
<joint
|
317 |
+
name="joint5"
|
318 |
+
type="revolute">
|
319 |
+
<origin
|
320 |
+
xyz="0 0 0"
|
321 |
+
rpy="1.5708 -0.087266 0" />
|
322 |
+
<parent
|
323 |
+
link="link4" />
|
324 |
+
<child
|
325 |
+
link="link5" />
|
326 |
+
<axis
|
327 |
+
xyz="0 0 1" />
|
328 |
+
<limit
|
329 |
+
lower="-1.22"
|
330 |
+
upper="1.22"
|
331 |
+
effort="100"
|
332 |
+
velocity="1" />
|
333 |
+
</joint>
|
334 |
+
<link
|
335 |
+
name="link6">
|
336 |
+
<inertial>
|
337 |
+
<origin
|
338 |
+
xyz="9.41121070072333E-09 0.000341209775988838 0.0342122921883722"
|
339 |
+
rpy="0 0 0" />
|
340 |
+
<mass
|
341 |
+
value="0.150196458571266" />
|
342 |
+
<inertia
|
343 |
+
ixx="4.31750564711759E-05"
|
344 |
+
ixy="-2.21295720427027E-08"
|
345 |
+
ixz="-3.27825836857102E-12"
|
346 |
+
iyy="9.99756357365307E-05"
|
347 |
+
iyz="1.10337380549335E-07"
|
348 |
+
izz="0.000118282295533688" />
|
349 |
+
</inertial>
|
350 |
+
<visual>
|
351 |
+
<origin
|
352 |
+
xyz="0 0 0"
|
353 |
+
rpy="0 0 0" />
|
354 |
+
<geometry>
|
355 |
+
<mesh
|
356 |
+
filename="link6.STL" />
|
357 |
+
</geometry>
|
358 |
+
<material
|
359 |
+
name="">
|
360 |
+
<color
|
361 |
+
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
362 |
+
</material>
|
363 |
+
</visual>
|
364 |
+
<collision>
|
365 |
+
<origin
|
366 |
+
xyz="0 0 0"
|
367 |
+
rpy="0 0 0" />
|
368 |
+
<geometry>
|
369 |
+
<mesh
|
370 |
+
filename="link6.STL" />
|
371 |
+
</geometry>
|
372 |
+
</collision>
|
373 |
+
</link>
|
374 |
+
<joint
|
375 |
+
name="joint6"
|
376 |
+
type="revolute">
|
377 |
+
<origin
|
378 |
+
xyz="0 0.091 0.0014165"
|
379 |
+
rpy="-1.5708 -1.5708 0" />
|
380 |
+
<parent
|
381 |
+
link="link5" />
|
382 |
+
<child
|
383 |
+
link="link6" />
|
384 |
+
<axis
|
385 |
+
xyz="0 0 1" />
|
386 |
+
<limit
|
387 |
+
lower="-3.14"
|
388 |
+
upper="3.14"
|
389 |
+
effort="100"
|
390 |
+
velocity="1" />
|
391 |
+
</joint>
|
392 |
+
|
393 |
+
<link
|
394 |
+
name="link7">
|
395 |
+
<inertial>
|
396 |
+
<origin
|
397 |
+
xyz="-0.000277795893713934 -0.046767350270289 -0.00921029791141448"
|
398 |
+
rpy="0 0 0" />
|
399 |
+
<mass
|
400 |
+
value="0.0264822500394006" />
|
401 |
+
<inertia
|
402 |
+
ixx="9.99782519244544E-06"
|
403 |
+
ixy="-1.57547595978589E-07"
|
404 |
+
ixz="-2.71355785017816E-08"
|
405 |
+
iyy="6.17952364356547E-06"
|
406 |
+
iyz="-1.58939504838734E-06"
|
407 |
+
izz="1.42102253390315E-05" />
|
408 |
+
</inertial>
|
409 |
+
<visual>
|
410 |
+
<origin
|
411 |
+
xyz="0 0 0"
|
412 |
+
rpy="0 0 0" />
|
413 |
+
<geometry>
|
414 |
+
<mesh
|
415 |
+
filename="link7.STL" />
|
416 |
+
</geometry>
|
417 |
+
<material
|
418 |
+
name="">
|
419 |
+
<color
|
420 |
+
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
421 |
+
</material>
|
422 |
+
</visual>
|
423 |
+
<collision>
|
424 |
+
<origin
|
425 |
+
xyz="0 0 0"
|
426 |
+
rpy="0 0 0" />
|
427 |
+
<geometry>
|
428 |
+
<mesh
|
429 |
+
filename="link7.STL" />
|
430 |
+
</geometry>
|
431 |
+
</collision>
|
432 |
+
</link>
|
433 |
+
<joint
|
434 |
+
name="joint7"
|
435 |
+
type="prismatic">
|
436 |
+
<origin
|
437 |
+
xyz="0 0 0.13503"
|
438 |
+
rpy="1.5708 0 1.5708" />
|
439 |
+
<parent
|
440 |
+
link="link6" />
|
441 |
+
<child
|
442 |
+
link="link7" />
|
443 |
+
<axis
|
444 |
+
xyz="0 0 -1" />
|
445 |
+
<limit
|
446 |
+
lower="-0.038"
|
447 |
+
upper="0"
|
448 |
+
effort="100"
|
449 |
+
velocity="1" />
|
450 |
+
</joint>
|
451 |
+
|
452 |
+
<link
|
453 |
+
name="link8">
|
454 |
+
<inertial>
|
455 |
+
<origin
|
456 |
+
xyz="0.000277795911672651 0.0467673513153836 -0.00921029799058583"
|
457 |
+
rpy="0 0 0" />
|
458 |
+
<mass
|
459 |
+
value="0.0264822490707451" />
|
460 |
+
<inertia
|
461 |
+
ixx="9.99782474142963E-06"
|
462 |
+
ixy="-1.57547666236405E-07"
|
463 |
+
ixz="2.71355834243046E-08"
|
464 |
+
iyy="6.17952362333486E-06"
|
465 |
+
iyz="1.58939503259658E-06"
|
466 |
+
izz="1.42102248648757E-05" />
|
467 |
+
</inertial>
|
468 |
+
<visual>
|
469 |
+
<origin
|
470 |
+
xyz="0 0 0"
|
471 |
+
rpy="0 0 0" />
|
472 |
+
<geometry>
|
473 |
+
<mesh
|
474 |
+
filename="link8.STL" />
|
475 |
+
</geometry>
|
476 |
+
<material
|
477 |
+
name="">
|
478 |
+
<color
|
479 |
+
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
480 |
+
</material>
|
481 |
+
</visual>
|
482 |
+
<collision>
|
483 |
+
<origin
|
484 |
+
xyz="0 0 0"
|
485 |
+
rpy="0 0 0" />
|
486 |
+
<geometry>
|
487 |
+
<mesh
|
488 |
+
filename="link8.STL" />
|
489 |
+
</geometry>
|
490 |
+
</collision>
|
491 |
+
</link>
|
492 |
+
<joint
|
493 |
+
name="joint8"
|
494 |
+
type="prismatic">
|
495 |
+
<origin
|
496 |
+
xyz="0 0 0.13503"
|
497 |
+
rpy="-1.5708 0 1.5708" />
|
498 |
+
<parent
|
499 |
+
link="link6" />
|
500 |
+
<child
|
501 |
+
link="link8" />
|
502 |
+
<axis
|
503 |
+
xyz="0 0 1" />
|
504 |
+
<limit
|
505 |
+
lower="0"
|
506 |
+
upper="0.038"
|
507 |
+
effort="100"
|
508 |
+
velocity="1" />
|
509 |
+
</joint>
|
510 |
+
<!-- <link
|
511 |
+
name="link8">
|
512 |
+
<inertial>
|
513 |
+
<origin
|
514 |
+
xyz="-0.000277795893713934 -0.046767350270289 -0.00921029791141448"
|
515 |
+
rpy="0 0 0" />
|
516 |
+
<mass
|
517 |
+
value="0.0264822500394006" />
|
518 |
+
<inertia
|
519 |
+
ixx="9.99782519244544E-06"
|
520 |
+
ixy="-1.57547595978589E-07"
|
521 |
+
ixz="-2.71355785017816E-08"
|
522 |
+
iyy="6.17952364356547E-06"
|
523 |
+
iyz="-1.58939504838734E-06"
|
524 |
+
izz="1.42102253390315E-05" />
|
525 |
+
</inertial>
|
526 |
+
<visual>
|
527 |
+
<origin
|
528 |
+
xyz="0 0 0"
|
529 |
+
rpy="0 0 0" />
|
530 |
+
<geometry>
|
531 |
+
<mesh
|
532 |
+
filename="link8.STL" />
|
533 |
+
</geometry>
|
534 |
+
<material
|
535 |
+
name="">
|
536 |
+
<color
|
537 |
+
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
538 |
+
</material>
|
539 |
+
</visual>
|
540 |
+
<collision>
|
541 |
+
<origin
|
542 |
+
xyz="0 0 0"
|
543 |
+
rpy="0 0 0" />
|
544 |
+
<geometry>
|
545 |
+
<mesh
|
546 |
+
filename="link8.STL" />
|
547 |
+
</geometry>
|
548 |
+
</collision>
|
549 |
+
</link>
|
550 |
+
<joint
|
551 |
+
name="joint8"
|
552 |
+
type="prismatic">
|
553 |
+
<origin
|
554 |
+
xyz="-0.037167 0 0.13503"
|
555 |
+
rpy="1.5708 0 1.5708" />
|
556 |
+
<parent
|
557 |
+
link="link6" />
|
558 |
+
<child
|
559 |
+
link="link8" />
|
560 |
+
<axis
|
561 |
+
xyz="0 0 -1" />
|
562 |
+
<limit
|
563 |
+
lower="-0.038"
|
564 |
+
upper="0"
|
565 |
+
effort="100"
|
566 |
+
velocity="1" />
|
567 |
+
</joint> -->
|
568 |
+
</robot>
|