forked from ipa320/schunk_modular_robotics
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathpg70.urdf.xacro
148 lines (131 loc) · 4.5 KB
/
pg70.urdf.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
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find schunk_description)/urdf/common.xacro" />
<xacro:include filename="$(find schunk_description)/urdf/pg70/pg70.gazebo.xacro" />
<xacro:include filename="$(find schunk_description)/urdf/pg70/pg70.transmission.xacro" />
<xacro:macro name="schunk_pg70" params="parent name *origin has_podest">
<xacro:if value="${has_podest}">
<joint name="${name}_podest_joint" type="fixed">
<xacro:insert_block name="origin" />
<parent link="${parent}"/>
<child link="${name}_podest_link"/>
</joint>
<link name="${name}_podest_link">
<xacro:default_inertial/>
<visual>
<origin xyz="0 0 0" rpy="0 ${M_PI} 0" />
<geometry>
<mesh filename="package://schunk_description/meshes/lwa4p/arm_base_link.stl" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 ${M_PI} 0" />
<geometry>
<mesh filename="package://schunk_description/meshes/lwa4p/arm_base_link.stl" />
</geometry>
</collision>
</link>
<joint name="${name}_palm_joint" type="fixed">
<origin xyz="0 0 0.10" rpy="0 0 0" />
<parent link="${name}_podest_link"/>
<child link="${name}_palm_link"/>
</joint>
</xacro:if>
<xacro:unless value="${has_podest}">
<joint name="${name}_palm_joint" type="fixed">
<xacro:insert_block name="origin" />
<parent link="${parent}"/>
<child link="${name}_palm_link" />
</joint>
</xacro:unless>
<link name="${name}_palm_link">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="1"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01" />
</inertial>
<visual>
<geometry>
<mesh filename="package://schunk_description/meshes/pg70/pg70.dae" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 ${0.040-0.5*0.0171}" rpy="0 0 0" />
<geometry>
<box size="0.082 0.114 0.080" />
</geometry>
</collision>
</link>
<joint name="${name}_finger_left_joint" type="prismatic" >
<origin xyz="0 0.0055 0.0789" rpy="0 0 0"/>
<parent link="${name}_palm_link" />
<child link="${name}_finger_left_link" />
<axis xyz="0 1 0" />
<limit effort="10" lower="-0.001" upper="0.0301" velocity="0.041"/>
</joint>
<link name="${name}_finger_left_link">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="1"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01" />
</inertial>
<visual>
<geometry>
<box size="0.03 0.01 0.01"/>
</geometry>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
</visual>
<collision>
<geometry>
<box size="0.03 0.01 0.01"/>
</geometry>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
</collision>
</link>
<joint name="${name}_finger_right_joint" type="prismatic" >
<origin xyz="0 -0.0055 0.0789" rpy="-0 0 0"/>
<parent link="${name}_palm_link" />
<child link="${name}_finger_right_link" />
<axis xyz="0 -1 0" />
<mimic joint="${name}_finger_left_joint" multiplier="1" offset="0"/>
<limit effort="10" lower="-0.001" upper="0.0301" velocity="0.041"/>
</joint>
<link name="${name}_finger_right_link">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="1"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01" />
</inertial>
<visual>
<geometry>
<box size="0.03 0.01 0.01"/>
</geometry>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
</visual>
<collision>
<geometry>
<box size="0.03 0.01 0.01"/>
</geometry>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
</collision>
</link>
<!-- extensions -->
<xacro:schunk_pg70_gazebo name="${name}" />
<xacro:schunk_pg70_transmission name="${name}" />
<!-- ros_control plugin -->
<gazebo>
<plugin name="ros_control" filename="libhwi_switch_gazebo_ros_control.so">
<robotNamespace>${name}</robotNamespace>
<filterJointsParam>joint_names</filterJointsParam>
</plugin>
</gazebo>
</xacro:macro>
</robot>