-
Notifications
You must be signed in to change notification settings - Fork 12
/
husky.urdf.xacro
executable file
·357 lines (313 loc) · 12.9 KB
/
husky.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
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
<?xml version="1.0"?>
<!--
Software License Agreement (BSD)
\file husky.urdf.xacro
\authors Paul Bovbel <[email protected]>, Devon Ash <[email protected]>
\copyright Copyright (c) 2015, Clearpath Robotics, Inc., All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that
the following conditions are met:
* Redistributions of source code must retain the above copyright notice, this list of conditions and the
following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the
following disclaimer in the documentation and/or other materials provided with the distribution.
* Neither the name of Clearpath Robotics nor the names of its contributors may be used to endorse or promote
products derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WAR-
RANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, IN-
DIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
-->
<robot name="husky" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:arg name="laser_enabled" default="false" />
<xacro:arg name="laser_xyz" default="$(optenv HUSKY_LMS1XX_XYZ 0.2206 0.0 0.00635)" />
<xacro:arg name="laser_rpy" default="$(optenv HUSKY_LMS1XX_RPY 0.0 0.0 0.0)" />
<xacro:arg name="kinect_enabled" default="false" />
<xacro:arg name="kinect_xyz" default="$(optenv HUSKY_KINECT_XYZ 0 0 0)" />
<xacro:arg name="kinect_rpy" default="$(optenv HUSKY_KINECT_RPY 0 0.18 3.14)" />
<xacro:property name="husky_front_bumper_extend" value="$(optenv HUSKY_FRONT_BUMPER_EXTEND 0)" />
<xacro:property name="husky_rear_bumper_extend" value="$(optenv HUSKY_REAR_BUMPER_EXTEND 0)" />
<xacro:arg name="robot_namespace" default="/" />
<xacro:arg name="urdf_extras" default="empty.urdf" />
<!-- Included URDF/XACRO Files -->
<xacro:include filename="$(find husky_description)/urdf/decorations.urdf.xacro" />
<xacro:include filename="$(find husky_description)/urdf/wheel.urdf.xacro" />
<xacro:include filename="$(find husky_description)/urdf/accessories/kinect_camera.urdf.xacro"/>
<xacro:include filename="$(find husky_description)/urdf/accessories/sick_lms1xx_mount.urdf.xacro"/>
<xacro:include filename="$(find husky_description)/urdf/accessories/sensor_arch.urdf.xacro"/>
<xacro:property name="M_PI" value="3.14159"/>
<!-- Base Size -->
<xacro:property name="base_x_size" value="0.98740000" />
<xacro:property name="base_y_size" value="0.57090000" />
<xacro:property name="base_z_size" value="0.24750000" />
<!-- Wheel Mounting Positions -->
<xacro:property name="wheelbase" value="0.5120" />
<xacro:property name="track" value="0.5708" />
<xacro:property name="wheel_vertical_offset" value="0.03282" />
<!-- Wheel Properties -->
<xacro:property name="wheel_length" value="0.1143" />
<xacro:property name="wheel_radius" value="0.1651" />
<!-- Base link is the center of the robot's bottom plate -->
<link name="base_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://husky_description/meshes/base_link.dae" />
</geometry>
</visual>
<collision>
<origin xyz="${( husky_front_bumper_extend - husky_rear_bumper_extend ) / 2.0} 0 ${base_z_size/4}" rpy="0 0 0" />
<geometry>
<box size="${ base_x_size + husky_front_bumper_extend + husky_rear_bumper_extend } ${base_y_size} ${base_z_size/2}"/>
</geometry>
</collision>
<collision>
<origin xyz="0 0 ${base_z_size*3/4-0.01}" rpy="0 0 0" />
<geometry>
<box size="${base_x_size*4/5} ${base_y_size} ${base_z_size/2-0.02}"/>
</geometry>
</collision>
</link>
<!-- Base footprint is on the ground under the robot -->
<link name="base_footprint"/>
<joint name="base_footprint_joint" type="fixed">
<origin xyz="0 0 ${wheel_vertical_offset - wheel_radius}" rpy="0 0 0" />
<parent link="base_link" />
<child link="base_footprint" />
</joint>
<!-- Interial link stores the robot's inertial information -->
<link name="inertial_link">
<inertial>
<mass value="46.034" />
<origin xyz="-0.00065 -0.085 0.062" />
<inertia ixx="0.6022" ixy="-0.02364" ixz="-0.1197" iyy="1.7386" iyz="-0.001544" izz="2.0296" />
</inertial>
</link>
<joint name="inertial_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="base_link" />
<child link="inertial_link" />
</joint>
<!-- IMU Link is the standard mounting position for the UM6 IMU.-->
<!-- Can be modified with environment variables in /etc/ros/setup.bash -->
<link name="imu_link"/>
<joint name="imu_joint" type="fixed">
<origin xyz="$(optenv HUSKY_IMU_XYZ 0.19 0 0.149)" rpy="$(optenv HUSKY_IMU_RPY 0 -1.5708 3.1416)" />
<parent link="base_link" />
<child link="imu_link" />
</joint>
<gazebo reference="imu_link">
</gazebo>
<!-- Camera_1 code start -->
<joint name="camera_joint_1" type="fixed">
<axis xyz="0 1 0" />
<origin xyz="0.35 0.025 0.02" rpy="0 0 0"/>
<parent link="top_plate_link"/>
<child link="camera_link_1"/>
</joint>
<!-- Camera -->
<link name="camera_link_1">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.02 0.02 0.02"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.02 0.02 0.02"/>
</geometry>
<material name="red"/>
</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>
<!-- Camera_1 code end -->
<!-- Camera_2 code start -->
<joint name="camera_joint_2" type="fixed">
<axis xyz="0 1 0" />
<origin xyz="0.35 -0.025 0.02" rpy="0 0 0"/>
<parent link="top_plate_link"/>
<child link="camera_link_2"/>
</joint>
<!-- Camera -->
<link name="camera_link_2">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.02 0.02 0.02"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.02 0.02 0.02"/>
</geometry>
<material name="red"/>
</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>
<!-- Camera_2 code end -->
<!-- Gazebo plugins -->
<gazebo reference="camera_link_1">
<material>Gazebo/Red</material>
<sensor type="camera" name="camera1">
<update_rate>30.0</update_rate>
<camera name="camera_1">
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<!-- Noise is sampled independently per pixel on each frame.
That pixel's noise value is added to each of its color
channels, which at that point lie in the range [0,1]. -->
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<cameraName>husky/camera1</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>camera_link_1</frameName>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
</sensor>
</gazebo>
<gazebo reference="camera_link_2">
<material>Gazebo/Red</material>
<sensor type="camera" name="camera2">
<update_rate>30.0</update_rate>
<camera name="camera_2">
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<!-- Noise is sampled independently per pixel on each frame.
That pixel's noise value is added to each of its color
channels, which at that point lie in the range [0,1]. -->
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<cameraName>husky/camera2</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>camera_link_2</frameName>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
</sensor>
</gazebo>
<!-- Husky wheel macros -->
<xacro:husky_wheel wheel_prefix="front_left">
<origin xyz="${wheelbase/2} ${track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:husky_wheel>
<xacro:husky_wheel wheel_prefix="front_right">
<origin xyz="${wheelbase/2} ${-track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:husky_wheel>
<xacro:husky_wheel wheel_prefix="rear_left">
<origin xyz="${-wheelbase/2} ${track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:husky_wheel>
<xacro:husky_wheel wheel_prefix="rear_right">
<origin xyz="${-wheelbase/2} ${-track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:husky_wheel>
<xacro:husky_decorate />
<xacro:if value="$(arg laser_enabled)">
<sick_lms1xx_mount prefix="base"/>
<sick_lms1xx frame="base_laser" topic="scan" robot_namespace="$(arg robot_namespace)"/>
<joint name="laser_mount_joint" type="fixed">
<origin xyz="$(arg laser_xyz)" rpy="$(arg laser_rpy)" />
<parent link="top_plate_link" />
<child link="base_laser_mount" />
</joint>
</xacro:if>
<xacro:if value="$(arg kinect_enabled)">
<xacro:sensor_arch prefix="" parent="top_plate_link">
<origin xyz="-0.35 0 0.51" rpy="0 0 -3.14"/>
</xacro:sensor_arch>
<joint name="kinect_frame_joint" type="fixed">
<origin xyz="$(arg kinect_xyz)" rpy="$(arg kinect_rpy)" />
<parent link="sensor_arch_mount_link"/>
<child link="camera_link"/>
</joint>
<xacro:kinect_camera prefix="camera" robot_namespace="$(arg robot_namespace)"/>
</xacro:if>
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>$(arg robot_namespace)</robotNamespace>
<legacyModeNS>true</legacyModeNS>
</plugin>
</gazebo>
<gazebo>
<plugin name="imu_controller" filename="libhector_gazebo_ros_imu.so">
<robotNamespace>$(arg robot_namespace)</robotNamespace>
<updateRate>50.0</updateRate>
<bodyName>base_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 name="gps_controller" filename="libhector_gazebo_ros_gps.so">
<robotNamespace>$(arg robot_namespace)</robotNamespace>
<updateRate>40</updateRate>
<bodyName>base_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>
<!-- Optional custom includes. -->
<xacro:include filename="$(arg urdf_extras)" />
</robot>