-
Notifications
You must be signed in to change notification settings - Fork 26
/
clearpathJackal.urdf
450 lines (444 loc) · 17.6 KB
/
clearpathJackal.urdf
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
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from jackal_description/urdf/jackal.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="jackal" xmlns:xacro="http://www.ros.org/wiki/xacro">
<material name="dark_grey">
<color rgba="0.2 0.2 0.2 1.0"/>
</material>
<material name="light_grey">
<color rgba="0.4 0.4 0.4 1.0"/>
</material>
<material name="yellow">
<color rgba="0.8 0.8 0.0 1.0"/>
</material>
<material name="black">
<color rgba="0.15 0.15 0.15 1.0"/>
</material>
<link name="front_left_wheel_link">
<visual>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://jackal_description/meshes/jackal-wheel.stl"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.04" radius="0.098"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.477"/>
<inertia ixx="0.0013" ixy="0" ixz="0" iyy="0.0024" iyz="0" izz="0.0013"/>
</inertial>
</link>
<gazebo reference="front_left_wheel_link">
<material>Gazebo/DarkGrey</material>
<selfCollide>false</selfCollide>
<mu1 value="0.5"/>
<mu2 value="0.5"/>
<kp value="10000000.0"/>
<kd value="1"/>
<fdir1 value="1 0 0"/>
</gazebo>
<joint name="front_left_wheel" type="continuous">
<parent link="chassis_link"/>
<child link="front_left_wheel_link"/>
<origin rpy="0 0 0" xyz="0.131 0.187795 0.0345"/>
<axis xyz="0 1 0"/>
</joint>
<!-- In reality, Jackal has only two motors, one per side. However, it's more
straightforward for Gazebo to simulate as if there's an actuator per wheel. -->
<transmission name="front_left_wheel_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="front_left_wheel">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="front_left_actuator">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<link name="front_right_wheel_link">
<visual>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://jackal_description/meshes/jackal-wheel.stl"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.04" radius="0.098"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.477"/>
<inertia ixx="0.0013" ixy="0" ixz="0" iyy="0.0024" iyz="0" izz="0.0013"/>
</inertial>
</link>
<gazebo reference="front_right_wheel_link">
<material>Gazebo/DarkGrey</material>
<selfCollide>false</selfCollide>
<mu1 value="0.5"/>
<mu2 value="0.5"/>
<kp value="10000000.0"/>
<kd value="1"/>
<fdir1 value="1 0 0"/>
</gazebo>
<joint name="front_right_wheel" type="continuous">
<parent link="chassis_link"/>
<child link="front_right_wheel_link"/>
<origin rpy="0 0 0" xyz="0.131 -0.187795 0.0345"/>
<axis xyz="0 1 0"/>
</joint>
<!-- In reality, Jackal has only two motors, one per side. However, it's more
straightforward for Gazebo to simulate as if there's an actuator per wheel. -->
<transmission name="front_right_wheel_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="front_right_wheel">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="front_right_actuator">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<link name="rear_left_wheel_link">
<visual>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://jackal_description/meshes/jackal-wheel.stl"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.04" radius="0.098"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.477"/>
<inertia ixx="0.0013" ixy="0" ixz="0" iyy="0.0024" iyz="0" izz="0.0013"/>
</inertial>
</link>
<gazebo reference="rear_left_wheel_link">
<material>Gazebo/DarkGrey</material>
<selfCollide>false</selfCollide>
<mu1 value="0.5"/>
<mu2 value="0.5"/>
<kp value="10000000.0"/>
<kd value="1"/>
<fdir1 value="1 0 0"/>
</gazebo>
<joint name="rear_left_wheel" type="continuous">
<parent link="chassis_link"/>
<child link="rear_left_wheel_link"/>
<origin rpy="0 0 0" xyz="-0.131 0.187795 0.0345"/>
<axis xyz="0 1 0"/>
</joint>
<!-- In reality, Jackal has only two motors, one per side. However, it's more
straightforward for Gazebo to simulate as if there's an actuator per wheel. -->
<transmission name="rear_left_wheel_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="rear_left_wheel">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="rear_left_actuator">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<link name="rear_right_wheel_link">
<visual>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://jackal_description/meshes/jackal-wheel.stl"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.04" radius="0.098"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.477"/>
<inertia ixx="0.0013" ixy="0" ixz="0" iyy="0.0024" iyz="0" izz="0.0013"/>
</inertial>
</link>
<gazebo reference="rear_right_wheel_link">
<material>Gazebo/DarkGrey</material>
<selfCollide>false</selfCollide>
<mu1 value="0.5"/>
<mu2 value="0.5"/>
<kp value="10000000.0"/>
<kd value="1"/>
<fdir1 value="1 0 0"/>
</gazebo>
<joint name="rear_right_wheel" type="continuous">
<parent link="chassis_link"/>
<child link="rear_right_wheel_link"/>
<origin rpy="0 0 0" xyz="-0.131 -0.187795 0.0345"/>
<axis xyz="0 1 0"/>
</joint>
<!-- In reality, Jackal has only two motors, one per side. However, it's more
straightforward for Gazebo to simulate as if there's an actuator per wheel. -->
<transmission name="rear_right_wheel_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="rear_right_wheel">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="rear_right_actuator">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<link name="base_link"/>
<joint name="base_link_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="base_link"/>
<child link="chassis_link"/>
</joint>
<link name="chassis_link">
<visual>
<origin rpy="1.57079632679 0 1.57079632679" xyz="0 0 -0.0655"/>
<geometry>
<mesh filename="package://jackal_description/meshes/jackal-base.stl"/>
</geometry>
<material name="dark_grey"/>
</visual>
<collision>
<origin xyz="0 0 0.092"/>
<geometry>
<box size="0.42 0.31 0.184"/>
</geometry>
</collision>
<inertial>
<!-- Center of mass -->
<origin rpy="0 0 0" xyz="0.012 0.002 0.067"/>
<mass value="16.523"/>
<!-- Moments of inertia: ( chassis without wheels ) -->
<inertia ixx="0.3136" ixy="-0.0008" ixz="0.0164" iyy="0.3922" iyz="-0.0009" izz="0.4485"/>
</inertial>
</link>
<link name="front_fender_link">
<visual>
<geometry>
<mesh filename="package://jackal_description/meshes/jackal-fender.stl"/>
</geometry>
<material name="yellow"/>
</visual>
</link>
<joint name="front_fender_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="chassis_link"/>
<child link="front_fender_link"/>
</joint>
<link name="rear_fender_link">
<visual>
<geometry>
<mesh filename="package://jackal_description/meshes/jackal-fender.stl"/>
</geometry>
<material name="yellow"/>
</visual>
</link>
<joint name="rear_fender_joint" type="fixed">
<origin rpy="0 0 3.14159265359" xyz="0 0 0"/>
<parent link="chassis_link"/>
<child link="rear_fender_link"/>
</joint>
<!-- TODO: Make this internal_imu_link or something, and use a mixed-in xacro
to supply the joint between it and imu_link. This is important so that imu_link
always points to the "active" IMU. When an upgrade IMU is connected, the
internal_imu_link should remain, but imu_link should point to the upgrade one. -->
<link name="imu_link">
<inertial>
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="1e-09" ixy="0.0" ixz="0.0" iyy="1e-09" iyz="0.0" izz="1e-09"/>
</inertial>
</link>
<joint name="imu_joint" type="fixed">
<parent link="chassis_link"/>
<child link="imu_link"/>
</joint>
<!-- TODO: Same note as applies to imu_link -->
<link name="navsat_link">
<visual>
<geometry>
<cylinder length="0.016" radius="0.026"/>
</geometry>
<origin xyz="0 0 0.008"/>
<material name="black"/>
</visual>
</link>
<joint name="navsat_joint" type="fixed">
<parent link="chassis_link"/>
<child link="navsat_link"/>
<origin xyz="-0.180 0.126 0.1815"/>
</joint>
<link name="mid_mount"/>
<joint name="mid_mount_joint" type="fixed">
<parent link="chassis_link"/>
<child link="mid_mount"/>
<origin xyz="0 0 0.184"/>
</joint>
<link name="rear_mount"/>
<joint name="rear_mount_joint" type="fixed">
<parent link="mid_mount"/>
<child link="rear_mount"/>
<origin xyz="-0.12 0 0"/>
</joint>
<link name="front_mount"/>
<joint name="front_mount_joint" type="fixed">
<parent link="mid_mount"/>
<child link="front_mount"/>
<origin xyz="0.12 0 0"/>
</joint>
<gazebo>
<plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
<robotNamespace>/</robotNamespace>
</plugin>
</gazebo>
<gazebo>
<plugin filename="libhector_gazebo_ros_imu.so" name="imu_controller">
<robotNamespace>/</robotNamespace>
<updateRate>50.0</updateRate>
<bodyName>imu_link</bodyName>
<topicName>imu/data</topicName>
<accelDrift>0.005 0.005 0.005</accelDrift>
<accelGaussianNoise>0.005 0.005 0.005</accelGaussianNoise>
<rateDrift>0.005 0.005 0.005 </rateDrift>
<rateGaussianNoise>0.005 0.005 0.005 </rateGaussianNoise>
<headingDrift>0.005</headingDrift>
<headingGaussianNoise>0.005</headingGaussianNoise>
</plugin>
</gazebo>
<gazebo>
<plugin filename="libhector_gazebo_ros_gps.so" name="gps_controller">
<updateRate>40</updateRate>
<robotNamespace>/</robotNamespace>
<bodyName>navsat_link</bodyName>
<frameId>base_link</frameId>
<topicName>/navsat/fix</topicName>
<velocityTopicName>/navsat/vel</velocityTopicName>
<referenceLatitude>49.9</referenceLatitude>
<referenceLongitude>8.9</referenceLongitude>
<referenceHeading>0</referenceHeading>
<referenceAltitude>0</referenceAltitude>
<drift>0.0001 0.0001 0.0001</drift>
</plugin>
</gazebo>
<gazebo reference="base_link">
<turnGravityOff>false</turnGravityOff>
</gazebo>
<gazebo reference="chassis_link">
<material>Gazebo/DarkGrey</material>
<turnGravityOff>false</turnGravityOff>
</gazebo>
<gazebo reference="imu_link">
<turnGravityOff>false</turnGravityOff>
</gazebo>
<gazebo reference="navsat_link">
<material>Gazebo/DarkGrey</material>
<turnGravityOff>false</turnGravityOff>
</gazebo>
<gazebo reference="front_fender_link">
<material>Gazebo/Yellow</material>
<turnGravityOff>false</turnGravityOff>
</gazebo>
<gazebo reference="rear_fender_link">
<material>Gazebo/Yellow</material>
<turnGravityOff>false</turnGravityOff>
</gazebo>
<!--
As you add to this URDF, please be aware that both the robot and
simulation include it. You must retain compatibility with all of
the following launch files:
jackal_viz/launch/view_model.launch
jackal_gazebo/launch/jackal_world.launch
jackal_base/launch/base.launch
-->
<!-- Common camera mounts and accessory URDFs. -->
<!-- <xacro:include filename="$(find jackal_description)/urdf/accessories/camera_mount.urdf.xacro" /> -->
<!-- <xacro:include filename="$(find pointgrey_camera_description)/urdf/pointgrey_flea3.urdf.xacro" /> -->
<!-- If enabled, generate the flea3 camera payload with a tilt of 30 degrees. -->
<!-- <xacro:if value="$(optenv JACKAL_FLEA3 0)">
<camera_mount prefix="$(optenv JACKAL_FLEA3_MOUNT front)"
tilt="$(optenv JACKAL_FLEA3_TILT 0.5236)"/>
<joint name="$(optenv JACKAL_FLEA3_MOUNT front)_camera_mount_joint" type="fixed">
<origin xyz="$(optenv JACKAL_FLEA3_OFFSET 0 0 0)"
rpy="$(optenv JACKAL_FLEA3_RPY 0 0 0)" />
<parent link="$(optenv JACKAL_FLEA3_MOUNT front)_mount" />
<child link="$(optenv JACKAL_FLEA3_MOUNT front)_camera_mount" />
</joint>
<pointgrey_flea3 frame="$(optenv JACKAL_FLEA3_MOUNT front)_camera" name="$(optenv JACKAL_FLEA3_NAME front)"
camera_x="0.0754" camera_y="0.029" camera_z="0.029"
camera_mass="0.085" hfov="1.0471975512" fps="60" width="640" height="512"/>
<joint name="$(optenv JACKAL_FLEA3_MOUNT front)_camera_bracket_joint" type="fixed">
<origin xyz="0.020 0 0.0245" rpy="0 0 0" />
<parent link="$(optenv JACKAL_FLEA3_MOUNT front)_camera_beam" />
<child link="$(optenv JACKAL_FLEA3_MOUNT front)_camera" />
</joint>
</xacro:if> -->
<!-- <xacro:include filename="$(find jackal_description)/urdf/accessories/stereo_camera_mount.urdf.xacro" /> -->
<!-- If enabled, generates a pair of flea3 cameras for stereo vision with a tilt of 30 degrees. -->
<!-- Disabled temporarily due to metapackage issue. -->
<!-- <xacro:if value="$(optenv JACKAL_STEREO_FLEA3 0)">
<stereo_camera_mount prefix="$(optenv JACKAL_FLEA3_MOUNT front)"
tilt="$(optenv JACKAL_FLEA3_TILT 0.5236)"/>
<joint name="$(optenv JACKAL_FLEA3_MOUNT front)_stereo_camera_mount_joint" type="fixed">
<origin xyz="$(optenv JACKAL_FLEA3_OFFSET 0 0 0)"
rpy="$(optenv JACKAL_FLEA3_RPY 0 0 0)" />
<parent link="$(optenv JACKAL_FLEA3_MOUNT front)_mount" />
<child link="$(optenv JACKAL_FLEA3_MOUNT front)_stereo_camera_mount" />
</joint>
<pointgrey_flea3 frame="$(optenv JACKAL_FLEA3_MOUNT front)_left_camera" name="$(optenv JACKAL_FLEA3_LEFT_NAME front/left)"
camera_x="0.0754" camera_y="0.029" camera_z="0.029"
camera_mass="0.085" hfov="1.0471975512" fps="60" width="640" height="512"/>
<joint name="$(optenv JACKAL_FLEA3_MOUNT front)_left_stereo_camera_bracket_joint" type="fixed">
<origin xyz="0.015 $(optenv JACKAL_STEREO_SEPERATION 0.16) 0.0599" rpy="0 0 0" />
<parent link="$(optenv JACKAL_FLEA3_MOUNT front)_stereo_camera_beam" />
<child link="$(optenv JACKAL_FLEA3_MOUNT front)_left_camera" />
</joint>
<pointgrey_flea3 frame="$(optenv JACKAL_FLEA3_MOUNT front)_right_camera" name="$(optenv JACKAL_FLEA3_RIGHT_NAME front/right)"
camera_x="0.0754" camera_y="0.029" camera_z="0.029"
camera_mass="0.085" hfov="1.0471975512" fps="60" width="640" height="512"/>
<joint name="$(optenv JACKAL_FLEA3_MOUNT front)_right_stereo_camera_bracket_joint" type="fixed">
<origin xyz="0.015 -$(optenv JACKAL_STEREO_SEPERATION 0.16) 0.0599" rpy="0 0 0" />
<parent link="$(optenv JACKAL_FLEA3_MOUNT front)_stereo_camera_beam" />
<child link="$(optenv JACKAL_FLEA3_MOUNT front)_right_camera" />
</joint>
</xacro:if> -->
<!-- If enabled, generate the bumblebee2 camera payload with a tilt of 0 degrees. -->
<!-- <xacro:include filename="$(find pointgrey_camera_description)/urdf/pointgrey_bumblebee2.urdf.xacro" /> -->
<!-- If enabled, generate the bumblebee2 camera payload with a tilt of 0 degrees. -->
<!-- Disabled temporarily due to metapackage issue. -->
<!-- <xacro:if value="$(optenv JACKAL_BB2 0)">
<camera_mount prefix="$(optenv JACKAL_BB2_MOUNT front)"
tilt="$(optenv JACKAL_BB2_TILT 0)"/>
<joint name="$(optenv JACKAL_BB2_MOUNT front)_camera_mount_joint" type="fixed">
<origin xyz="$(optenv JACKAL_BB2_OFFSET 0 0 0)"
rpy="$(optenv JACKAL_BB2_RPY 0 0 0)" />
<parent link="$(optenv JACKAL_BB2_MOUNT front)_mount" />
<child link="$(optenv JACKAL_BB2_MOUNT front)_camera_mount" />
</joint>
<BB2-08S2C-38 frame="$(optenv JACKAL_BB2_MOUNT front)_camera" name="$(optenv JACKAL_BB2_NAME front)" />
<joint name="$(optenv JACKAL_BB2_MOUNT front)_camera_bracket_joint" type="fixed">
<origin xyz="0.007 0 0.02450" rpy="0 0 0" />
<parent link="$(optenv JACKAL_BB2_MOUNT front)_camera_beam" />
<child link="$(optenv JACKAL_BB2_MOUNT front)_camera" />
</joint>
</xacro:if> -->
<!-- This file is a placeholder which is included by default from
jackal.urdf.xacro. If a robot is being customized and requires
additional URDF, set the JACKAL_URDF_EXTRAS environment variable
to the full path of the file you would like included. -->
</robot>