-
Notifications
You must be signed in to change notification settings - Fork 38
/
simple_arm.urdf.xacro
245 lines (230 loc) · 8.16 KB
/
simple_arm.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
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
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
<?xml version="1.0"?>
<robot name="simple_arm" xmlns:xacro="http://www.ros.org/wiki/xacro">
<!--Define constants-->
<xacro:property name="link_type" value="cuboidal" />
<xacro:property name="PI" value="3.14159"/>
<xacro:property name="mass1" value="50" />
<xacro:property name="mass2" value="10" />
<xacro:property name="mass3" value="1" />
<xacro:property name="radius1" value="0.3" /> <!--base_link radius-->
<xacro:property name="radius2" value="0.1" /> <!--link_1 radius-->
<xacro:property name="radius3" value="0.1" /> <!--link_2 radius-->
<xacro:property name="length1" value="0.2" /> <!--link_1 length-->
<xacro:property name="length2" value="1.0" /> <!--link_2 length-->
<xacro:property name="length3" value="0.75" /> <!--link_3 length-->
<xacro:property name="camera_size" value="0.05" />
<!--Import gazebo elements-->
<xacro:include filename="$(find simple_arm)/urdf/simple_arm.gazebo.xacro" />
<!--Links-->
<link name="world"/>
<link name="base_link">
<visual>
<origin xyz="0 0 ${length1/2}" rpy="0 0 0"/>
<geometry>
<cylinder length="${length1}" radius="${radius1}"/>
</geometry>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 ${length1/2}" rpy="0 0 0"/>
<geometry>
<cylinder length="${length1}" radius="${radius1}"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 ${length1/2}" rpy="0 0 0"/>
<mass value="${mass1}"/>
<inertia
ixx="${mass1 / 12.0 * (2*radius1*2*radius1 + length1*length1)}" ixy="0.0" ixz="0.0"
iyy="${mass1 / 12.0 * (length1*length1 + 2*radius1*2*radius1)}" iyz="0.0"
izz="${mass1 / 12.0 * (2*radius1*2*radius1 + 2*radius1*2*radius1)}"/>
</inertial>
</link>
<!--Cuboidal link_1-->
<xacro:if value="${link_type == 'cuboidal'}">
<link name="link_1">
<visual>
<origin xyz="0 0 ${length2/2}" rpy="0 0 0"/>
<geometry>
<box size="${2*radius2} ${2*radius2} ${length2}"/>
</geometry>
<material name="blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 ${length2/2}" rpy="0 0 0"/>
<geometry>
<box size="${2*radius2} ${2*radius2} ${length2}"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 ${length2/2}" rpy="0 0 0"/>
<mass value="${mass2}"/>
<inertia
ixx="${mass2 / 12.0 * (2*radius2*2*radius2 + length2*length2)}" ixy="0.0" ixz="0.0"
iyy="${mass2 / 12.0 * (length2*length2 + 2*radius2*2*radius2)}" iyz="0.0"
izz="${mass2 / 12.0 * (2*radius2*2*radius2 + 2*radius2*2*radius2)}"/>
</inertial>
</link>
</xacro:if>
<!--Cylindrical link_1-->
<xacro:if value="${link_type == 'cylindrical'}">
<link name="link_1">
<visual>
<origin xyz="0 0 ${length2/2}" rpy="0 0 0"/>
<geometry>
<cylinder length="${length2}" radius="${radius2}"/>
</geometry>
<material name="blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 ${length2/2}" rpy="0 0 0"/>
<geometry>
<cylinder length="${length2}" radius="${radius2}"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 ${length2/2}" rpy="0 0 0"/>
<mass value="${mass2}"/>
<inertia
ixx="${mass2 / 12.0 * (2*radius2*2*radius2 + length2*length2)}" ixy="0.0" ixz="0.0"
iyy="${mass2 / 12.0 * (length2*length2 + 2*radius2*2*radius2)}" iyz="0.0"
izz="${mass2 / 12.0 * (2*radius2*2*radius2 + 2*radius2*2*radius2)}"/>
</inertial>
</link>
</xacro:if>
<!--Cuboidal link_2-->
<xacro:if value="${link_type == 'cuboidal'}">
<link name="link_2">
<visual>
<origin xyz="0 0 ${length3/2}" rpy="0 0 0"/>
<geometry>
<box size="${2*radius3} ${2*radius3} ${length3}"/>
</geometry>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 ${length3/2}" rpy="0 0 0"/>
<geometry>
<box size="${2*radius3} ${2*radius3} ${length3}"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 ${length3/2}" rpy="0 0 0"/>
<mass value="${mass3}"/>
<inertia
ixx="${mass3 / 12.0 * (2*radius3*2*radius3 + length3*length3)}" ixy="0.0" ixz="0.0"
iyy="${mass3 / 12.0 * (length3*length3 + 2*radius3*2*radius3)}" iyz="0.0"
izz="${mass3 / 12.0 * (2*radius3*2*radius3 + 2*radius3*2*radius3)}"/>
</inertial>
</link>
</xacro:if>
<!--Cylindrical link_2-->
<xacro:if value="${link_type == 'cylindrical'}">
<link name="link_2">
<visual>
<origin xyz="0 0 ${length3/2}" rpy="0 0 0"/>
<geometry>
<cylinder length="${length3}" radius="${radius3}"/>
</geometry>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 ${length3/2}" rpy="0 0 0"/>
<geometry>
<cylinder length="${length3}" radius="${radius3}"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 ${length3/2}" rpy="0 0 0"/>
<mass value="${mass3}"/>
<inertia
ixx="${mass3 / 12.0 * (2*radius3*2*radius3 + length3*length3)}" ixy="0.0" ixz="0.0"
iyy="${mass3 / 12.0 * (length3*length3 + 2*radius3*2*radius3)}" iyz="0.0"
izz="${mass3 / 12.0 * (2*radius3*2*radius3 + 2*radius3*2*radius3)}"/>
</inertial>
</link>
</xacro:if>
<!--camera_link-->
<link name="camera_link">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<!--mesh filename="package://simple_arm/meshes/camera.dae"/-->
<sphere radius="${camera_size}"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<!--mesh filename="package://simple_arm/meshes/camera.dae"/-->
<sphere radius="${camera_size}"/>
</geometry>
<material name="red">
<color rgba="1.0 0 0 1.0"/>
</material>
</visual>
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
</link>
<!--Joints-->
<joint name="fixed_base_joint" type="fixed">
<parent link="world"/>
<child link="base_link"/>
</joint>
<joint name="joint_1" type="continuous">
<parent link="base_link"/>
<child link="link_1"/>
<axis xyz="0 0 1"/>
<origin xyz="0 0 ${length1}" rpy="0 0 0"/>
<limit effort="30" velocity="1.0"/>
<safety_controller k_velocity="10" k_position="15" soft_lower_limit="-2.0" soft_upper_limit="0.5" />
</joint>
<joint name="joint_2" type="continuous">
<parent link="link_1"/>
<child link="link_2"/>
<axis xyz="0 1 0"/>
<origin xyz="0 ${2*radius2} ${length2-radius2}" rpy="0 0 0"/>
<limit effort="30" velocity="1.0"/>
<safety_controller k_velocity="10" k_position="15" soft_lower_limit="-2.0" soft_upper_limit="0.5" />
</joint>
<joint name="camera_joint" type="fixed">
<axis xyz="0 0 1" />
<origin xyz="0 0 ${length3}" rpy="0 -${PI/2} 0"/>
<parent link="link_2"/>
<child link="camera_link"/>
</joint>
<!--Transmission and actuators-->
<transmission name="tran1">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint_1">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor1">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="tran2">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint_2">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor2">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</robot>