-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathpzn_plus.xacro
49 lines (40 loc) · 1.87 KB
/
pzn_plus.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
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!--degrees to radians-->
<xacro:macro name="pzn_plus" params="prefix_1 prefix_2 meshType">
<!-- imports -->
<xacro:include filename="$(find pzn_plus_description)/urdf/pzn_plus_base_link.urdf.xacro" />
<xacro:include filename="$(find pzn_plus_description)/urdf/pzn_plus_fingers_link.urdf.xacro" />
<!--xacro:include filename="$(find pzn_plus_description)/urdf/pzn_plus.gazebo.xacro" /-->
<xacro:include filename="$(find pzn_plus_description)/urdf/pzn_plus.transmission.urdf.xacro" />
<xacro:pzn_plus_base_link prefix="${prefix_1}_" meshType="${meshType}" />
<xacro:pzn_plus_fingers_link prefix="${prefix_2}_" meshType="${meshType}" />
<xacro:pzn_plus_transmission prefix="${prefix_2}_" />
<!-- links -->
<!--link name="world" /-->
<!--
<joint name="fixed" type="fixed">
<parent link="world" />
<child link="${prefix}base_link" />
</joint>
-->
<joint name="${prefix_1}_finger_1" type="fixed">
<origin xyz="-0.00147 0.0005 0.0050134" rpy="0 0 0" />
<parent link="${prefix_1}_trans_1" />
<child link="${prefix_2}_finger_1" />
<axis xyz="0 0 0" />
</joint>
<joint name="${prefix_1}_finger_2" type="fixed">
<origin xyz="-0.00147 0.0005 0.00501343290293372" rpy="0 0 0" />
<parent link="${prefix_1}_trans_2" />
<child link="${prefix_2}_finger_2" />
<axis xyz="0 0 0" />
</joint>
<joint name="${prefix_1}_finger_3" type="fixed">
<origin xyz="-0.00147 0.0005 0.00501343290293372" rpy="0 0 0" />
<parent link="${prefix_1}_trans_3" />
<child link="${prefix_2}_finger_3" />
<axis xyz="0 0 0" />
</joint>
</xacro:macro>
</robot>