forked from mintar/mir_robot
-
Notifications
You must be signed in to change notification settings - Fork 2
/
mir_100_v1.urdf.xacro
275 lines (240 loc) · 11.8 KB
/
mir_100_v1.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
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find mir_description)/urdf/include/common_properties.urdf.xacro" />
<xacro:include filename="$(find mir_description)/urdf/include/imu.gazebo.urdf.xacro" />
<xacro:include filename="$(find mir_description)/urdf/include/mir_100.gazebo.xacro" />
<xacro:include filename="$(find mir_description)/urdf/include/mir_100.transmission.xacro" />
<xacro:include filename="$(find mir_description)/urdf/include/sick_s300.urdf.xacro" />
<xacro:property name="deg_to_rad" value="0.017453293" />
<xacro:property name="mir_100_base_mass" value="58.0" />
<xacro:property name="mir_100_act_wheel_radius" value="0.0625" />
<xacro:property name="mir_100_act_wheel_width" value="0.032" />
<xacro:property name="mir_100_act_wheel_mass" value="1.0" />
<xacro:property name="mir_100_act_wheel_dx" value="0.037646" />
<xacro:property name="mir_100_act_wheel_dy" value="0.222604" />
<xacro:property name="mir_100_caster_wheel_radius" value="${mir_100_act_wheel_radius}" />
<xacro:property name="mir_100_caster_wheel_width" value="${mir_100_act_wheel_width}" />
<xacro:property name="mir_100_caster_wheel_mass" value="${mir_100_act_wheel_mass}" />
<xacro:property name="mir_100_caster_wheel_dx" value="-0.0382" />
<xacro:property name="mir_100_caster_wheel_dy" value="0" />
<xacro:property name="mir_100_caster_wheel_dz" value="-0.094" />
<xacro:property name="mir_100_front_caster_wheel_base_dx" value="0.341346" />
<xacro:property name="mir_100_back_caster_wheel_base_dx" value="-0.270154" />
<xacro:property name="mir_100_caster_wheel_base_dy" value="0.203" />
<xacro:property name="mir_100_caster_wheel_base_dz" value="${mir_100_caster_wheel_radius-mir_100_caster_wheel_dz}" />
<xacro:property name="imu_stdev" value="0.00017" />
<xacro:macro name="actuated_wheel" params="prefix locationprefix locationright">
<joint name="${prefix}${locationprefix}_wheel_joint" type="continuous">
<origin xyz="0.0 ${-mir_100_act_wheel_dy * locationright} ${mir_100_act_wheel_radius}" rpy="0 0 0" />
<parent link="${prefix}base_link" />
<child link="${prefix}${locationprefix}_wheel_link" />
<axis xyz="0 1 0" />
<limit effort="100" velocity="20.0" />
</joint>
<link name="${prefix}${locationprefix}_wheel_link">
<xacro:cylinder_inertial mass="${mir_100_act_wheel_mass}" radius="${mir_100_act_wheel_radius}" length="${mir_100_act_wheel_width}">
<origin xyz="0 0 0" rpy="${0.5 * pi} 0 0" />
</xacro:cylinder_inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://mir_description/meshes/visual/wheel.stl" />
</geometry>
<xacro:insert_block name="material_dark_grey" />
</visual>
<collision>
<origin xyz="0 0 0" rpy="${pi/2} 0 0" />
<geometry>
<cylinder radius="${mir_100_act_wheel_radius}" length="${mir_100_act_wheel_width}" />
</geometry>
</collision>
</link>
<gazebo reference="${prefix}${locationprefix}_wheel_link">
<material>Gazebo/DarkGrey</material>
</gazebo>
</xacro:macro>
<xacro:macro name="caster_wheel" params="prefix ns locationprefix locationright wheel_base_dx">
<!-- caster hub -->
<joint name="${prefix}${locationprefix}_caster_rotation_joint" type="continuous">
<origin xyz="${wheel_base_dx} ${-mir_100_caster_wheel_base_dy * locationright} ${mir_100_caster_wheel_base_dz}" rpy="0 0 0" />
<parent link="${prefix}base_link" />
<child link="${prefix}${locationprefix}_caster_rotation_link" />
<axis xyz="0 0 1" />
<dynamics damping="0.01" friction="0.0"/>
</joint>
<gazebo>
<plugin name="${locationprefix}_caster_rotation_joint_states" filename="libgazebo_ros_joint_state_publisher.so">
<ros>
<namespace>${ns}</namespace>
</ros>
<update_rate>200.0</update_rate>
<joint_name>${prefix}${locationprefix}_caster_rotation_joint</joint_name>
</plugin>
</gazebo>
<link name="${prefix}${locationprefix}_caster_rotation_link">
<inertial>
<!-- <origin xyz="0 0 -0.042500000044" rpy="${0.5 * pi} ${24 * deg_to_rad} ${1.5 * pi}" /> -->
<origin xyz="0 0 -0.042500000044" rpy="${24 * deg_to_rad} 0 ${0.5 * pi} " />
<mass value="0.3097539019" />
<inertia
ixx="0.0005844517978"
ixy="0"
ixz="0"
iyy="0.00052872551237"
iyz="0"
izz="0.00017923555074" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://mir_description/meshes/visual/caster_wheel_base.stl" />
</geometry>
<xacro:insert_block name="material_silver" />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://mir_description/meshes/collision/caster_wheel_base.stl" />
</geometry>
</collision>
</link>
<gazebo reference="${prefix}${locationprefix}_caster_rotation_link">
<material>Gazebo/Grey</material>
</gazebo>
<!-- caster wheel -->
<joint name="${prefix}${locationprefix}_caster_wheel_joint" type="continuous">
<origin xyz="${mir_100_caster_wheel_dx} ${-mir_100_caster_wheel_dy * locationright} ${mir_100_caster_wheel_dz}" rpy="0 0 0" />
<parent link="${prefix}${locationprefix}_caster_rotation_link" />
<child link="${prefix}${locationprefix}_caster_wheel_link" />
<axis xyz="0 1 0" />
</joint>
<gazebo>
<plugin name="${locationprefix}_caster_wheel_joint_states" filename="libgazebo_ros_joint_state_publisher.so">
<ros>
<namespace>${ns}</namespace>
</ros>
<update_rate>200.0</update_rate>
<joint_name>${prefix}${locationprefix}_caster_wheel_joint</joint_name>
</plugin>
</gazebo>
<link name="${prefix}${locationprefix}_caster_wheel_link">
<xacro:cylinder_inertial mass="${mir_100_caster_wheel_mass}" radius="${mir_100_caster_wheel_radius}" length="${mir_100_caster_wheel_width}">
<origin xyz="0 0 0" rpy="${0.5 * pi} 0 0" />
</xacro:cylinder_inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://mir_description/meshes/visual/wheel.stl" />
</geometry>
<xacro:insert_block name="material_dark_grey" />
</visual>
<collision>
<origin xyz="0 0 0" rpy="${pi/2} 0 0" />
<geometry>
<cylinder radius="${mir_100_caster_wheel_radius}" length="${mir_100_caster_wheel_width}" />
</geometry>
</collision>
</link>
<gazebo reference="${prefix}${locationprefix}_caster_wheel_link">
<material>Gazebo/DarkGrey</material>
</gazebo>
</xacro:macro>
<xacro:macro name="mir_100" params="prefix ns">
<link name="${prefix}base_footprint" />
<joint name="${prefix}base_joint" type="fixed">
<parent link="${prefix}base_footprint" />
<child link="${prefix}base_link" />
<origin xyz="0 0 0" rpy="0 0 0" />
</joint>
<link name="${prefix}base_link">
<xacro:box_inertial mass="${mir_100_base_mass}" x="0.9" y="0.58" z="0.3">
<origin xyz="${mir_100_act_wheel_dx} 0 0.20" rpy="0 0 0" />
</xacro:box_inertial>
<visual>
<origin xyz="${mir_100_act_wheel_dx} 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://mir_description/meshes/visual/mir_100_base.stl" />
</geometry>
<xacro:insert_block name="material_white" />
</visual>
<collision>
<origin xyz="${mir_100_act_wheel_dx} 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://mir_description/meshes/collision/mir_100_base.stl" />
</geometry>
</collision>
</link>
<gazebo reference="${prefix}base_link">
<material>Gazebo/White</material>
</gazebo>
<!-- IMU -->
<joint name="${prefix}base_link_to_imu_joint" type="fixed">
<parent link="${prefix}base_link" />
<child link="${prefix}imu_link" />
<origin xyz="0.0 0.0 0.25" rpy="0 0 0" /> <!-- same as real MiR -->
</joint>
<link name="${prefix}imu_link" />
<xacro:imu_gazebo link="${prefix}imu_link" imu_topic="${prefix}imu_data" update_rate="50.0" stdev="${imu_stdev}" />
<!-- Create an alias for imu_link. This is necessary because the real MiR's
TF has imu_link, but the imu_data topic is published in the imu_frame
frame. -->
<joint name="${prefix}imu_link_to_imu_frame_joint" type="fixed">
<parent link="${prefix}imu_link" />
<child link="${prefix}imu_frame" />
<origin xyz="0 0 0" rpy="0 0 0" />
</joint>
<link name="${prefix}imu_frame" />
<!-- Laser scanners -->
<!-- virtual link for merged laserscan-->
<joint name="${prefix}base_link_to_virtual_laser_joint" type="fixed">
<parent link="${prefix}base_link" />
<child link="${prefix}virtual_laser_link" />
<origin xyz="0.0 0.0 0.25" rpy="0.0 0.0 0" />
</joint>
<link name="${prefix}virtual_laser_link">
</link>
<joint name="${prefix}base_link_to_front_laser_joint" type="fixed">
<parent link="${prefix}base_link" />
<child link="${prefix}front_laser_link" />
<origin xyz="0.4288 0.2358 0.1914" rpy="0.0 0.0 ${0.25 * pi}" /> <!-- from visually matching up the meshes of the MiR and the laser scanner -->
</joint>
<xacro:sick_s300 prefix="${prefix}" link="front_laser_link" topic="f_scan" />
<joint name="${prefix}base_link_to_back_laser_joint" type="fixed">
<parent link="${prefix}base_link" />
<child link="${prefix}back_laser_link" />
<origin xyz="-0.3548 -0.2352 0.1914" rpy="0.0 0.0 ${-0.75 * pi}" /> <!-- from visually matching up the meshes of the MiR and the laser scanner -->
</joint>
<xacro:sick_s300 prefix="${prefix}" link="back_laser_link" topic="b_scan" />
<!-- Ultrasound sensors -->
<joint name="${prefix}us_1_joint" type="fixed"> <!-- right ultrasound -->
<parent link="${prefix}base_link" />
<child link="${prefix}us_1_frame" />
<origin xyz="0.45 -0.12 0.16 " rpy="0 0 0" /> <!-- from visually matching to the mesh of the MiR -->
</joint>
<link name="${prefix}us_1_frame" />
<joint name="${prefix}us_2_joint" type="fixed"> <!-- left ultrasound -->
<parent link="${prefix}base_link" />
<child link="${prefix}us_2_frame" />
<origin xyz="0.45 0.12 0.16 " rpy="0 0 0" /> <!-- from visually matching to the mesh of the MiR -->
</joint>
<link name="${prefix}us_2_frame" />
<!-- wheels -->
<xacro:actuated_wheel prefix="${prefix}" locationprefix="left" locationright="-1"/>
<xacro:actuated_wheel prefix="${prefix}" locationprefix="right" locationright="1"/>
<xacro:caster_wheel prefix="${prefix}" ns="${ns}" locationprefix="fl" locationright="-1" wheel_base_dx="${mir_100_front_caster_wheel_base_dx}"/>
<xacro:caster_wheel prefix="${prefix}" ns="${ns}" locationprefix="fr" locationright="1" wheel_base_dx="${mir_100_front_caster_wheel_base_dx}"/>
<xacro:caster_wheel prefix="${prefix}" ns="${ns}" locationprefix="bl" locationright="-1" wheel_base_dx="${mir_100_back_caster_wheel_base_dx}"/>
<xacro:caster_wheel prefix="${prefix}" ns="${ns}" locationprefix="br" locationright="1" wheel_base_dx="${mir_100_back_caster_wheel_base_dx}"/>
<joint name="${prefix}base_link_surface_joint" type="fixed">
<origin xyz="${mir_100_act_wheel_dx} 0 0.352" rpy="0 0 0" />
<parent link="${prefix}base_link" />
<child link="${prefix}surface" />
<axis xyz="0 0 1" />
</joint>
<link name="${prefix}surface"/>
<xacro:mir_100_wheel_transmissions prefix="${prefix}"/>
<!-- set the gazebo friction parameters for the wheels -->
<xacro:set_all_wheel_frictions prefix="${prefix}"/>
<xacro:p3d_base_controller prefix="${prefix}" />
</xacro:macro>
</robot>