-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathmacros.xacro
271 lines (247 loc) · 11.5 KB
/
macros.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
<?xml version="1.0" ?>
<robot name="zinger" xmlns:xacro="http://www.ros.org/wiki/xacro" >
<!--
A macro to create a wheel link and the joint for the wheel
Parameters:
- name: Name of the wheel, e.g. left_rear
- mass: Mass of the wheel in kilogram
- radius: Radius of the wheel in meters
- width: Width of the wheel in meters
- offset: The distance between the wheel and the steering plate above the wheel. In meters.
-->
<xacro:macro name="wheel_assembly" params="name mass radius width offset">
<joint name="joint_steering_to_wheel_${name}" type="continuous">
<origin rpy="0 0 0" xyz="0 0 ${-1 * (radius + offset)}"/>
<parent link="link_steering_${name}"/>
<child link="link_wheel_${name}"/>
<axis xyz="0.0 1.0 0.0"/>
</joint>
<link name="link_wheel_${name}">
<inertial>
<origin xyz="0 0 0" rpy="${PI/2} 0 0" />
<mass value="${mass}"/>
<inertia
ixx="${(mass/12) * (3*radius*radius + width*width)}"
ixy="0"
ixz="0"
iyy="${(mass/12) * (3*radius*radius + width*width)}"
iyz="0"
izz="${(mass/2) * (radius*radius)}"/>
</inertial>
<visual>
<origin rpy="${PI/2} 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="${width}" radius="${radius}" />
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="${PI/2} 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="${width}" radius="${radius}" />
</geometry>
</collision>
</link>
</xacro:macro>
<!--
A macro to create a steering link and the joint for the steering unit
Parameters:
- name: Name of the steering unit, e.g. left_rear
- mass: Mass of the steering unit in kilogram
- chassis_length: The length of the chassis
- chassis_width: The width of the chassis
- chassis_height: The height of the chassis
- steering_radius: Radius of the steering unit in meters
- wheel_radius: Radius of the wheel in meters
- thickness: Thickness of the steering unit
- offset: The distance between the wheel and the steering plate above the wheel. In meters.
- x_reflect: Direction multiplier for X offsets. Either 1 or -1
- y_reflect: Direction multiplier for Y offsets. Either 1 or -1
-->
<xacro:macro name="steering_assembly" params="name mass chassis_length chassis_width chassis_height steering_radius thickness wheel_radius offset x_reflect y_reflect">
<joint name="joint_chassis_to_steering_${name}" type="continuous">
<origin rpy="0 0 0" xyz="${x_reflect * (0.5 * chassis_length - steering_radius)} ${y_reflect * (0.5 * chassis_width + steering_radius)} ${0.5 * chassis_height - 0.5 * thickness}"/>
<parent link="chassis_link"/>
<child link="link_steering_${name}"/>
<axis xyz="0.0 0.0 1.0"/>
</joint>
<link name="link_steering_${name}">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="${mass}"/>
<inertia
ixx="${(mass/12) * (3*steering_radius*steering_radius + thickness*thickness)}"
ixy="0"
ixz="0"
iyy="${(mass/12) * (3*steering_radius*steering_radius + thickness*thickness)}"
iyz="0"
izz="${(mass/2) * (steering_radius*steering_radius)}"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="${thickness}" radius="${steering_radius}" />
</geometry>
<material name="blue"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="${thickness}" radius="${steering_radius}" />
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 ${y_reflect * wheel_radius} ${-1 * 0.5 * (thickness + wheel_radius + 2 * offset)}"/>
<geometry>
<box size="${wheel_radius} 0.01 ${wheel_radius + 2 * offset}" />
</geometry>
<material name="blue"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 ${y_reflect * wheel_radius} ${-1 * 0.5 * (thickness + wheel_radius + 2 * offset)}"/>
<geometry>
<box size="${wheel_radius} 0.01 ${wheel_radius + 2 * offset}" />
</geometry>
</collision>
</link>
</xacro:macro>
<!--
A macro to create a wheel link and the joint for the wheel
Parameters:
- name: Name of the wheel, e.g. left_rear
- chassis_length: The length of the chassis
- chassis_width: The width of the chassis
- chassis_height: The height of the chassis
- wheel_mass: Mass of the wheel in kilogram
- wheel_radius: Radius of the wheel in meters
- wheel_width: Width of the wheel in meters
- offset: The distance between the wheel and the steering plate above the wheel. In meters.
- x_reflect: Direction multiplier for X offsets. Either 1 or -1
- y_reflect: Direction multiplier for Y offsets. Either 1 or -1
-->
<xacro:macro name="drive_module_assembly" params="name chassis_length chassis_width chassis_height wheel_mass wheel_radius wheel_width steering_mass steering_radius steering_thickness offset x_reflect y_reflect">
<xacro:steering_assembly
name="${name}"
mass="${steering_mass}"
chassis_length="${chassis_length}"
chassis_width="${chassis_width}"
chassis_height="${chassis_height}"
steering_radius="${steering_radius}"
thickness="${steering_thickness}"
wheel_radius="${wheel_radius}"
offset="${offset}"
x_reflect="${x_reflect}"
y_reflect="${y_reflect}"/>
<xacro:wheel_assembly
name="${name}"
mass="${wheel_mass}"
radius="${wheel_radius}"
width="${wheel_width}"
offset="${offset + 0.5 * steering_thickness}"/>
</xacro:macro>
<!-- CONTROLLERS -->
<xacro:macro name="steering_module_controller" params="name">
<joint name="joint_chassis_to_steering_${name}">
<command_interface name="position">
<param name="min">-${2 * PI}</param>
<param name="max">${2 * PI}</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
</joint>
<joint name="joint_steering_to_wheel_${name}">
<command_interface name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
</joint>
</xacro:macro>
<!-- SENSORS -->
<!-- IMU sensor -->
<xacro:macro name="sensor_imu" params="name parent_link *origin">
<xacro:property name="mass" value="0.01"/>
<xacro:property name="length_x" value="0.01" />
<xacro:property name="length_y" value="0.01" />
<xacro:property name="length_z" value="0.01" />
<xacro:property name="collision_x_offset" value="0.005" />
<xacro:property name="collision_y_offset" value="0.005" />
<xacro:property name="collision_z_offset" value="${0.5 * length_z}" />
<joint name="joint_body_to_sensor_imu_${name}" type="fixed">
<xacro:insert_block name="origin"/>
<parent link="${parent_link}"/>
<child link="link_sensor_imu_${name}"/>
</joint>
<link name="link_sensor_imu_${name}">
<visual>
<origin xyz="${collision_x_offset} ${collision_y_offset} ${collision_z_offset}"/>
<geometry>
<box size="${length_x} ${length_y} ${length_z}"/>
</geometry>
</visual>
<collision>
<origin xyz="${collision_x_offset} ${collision_y_offset} ${collision_z_offset}"/>
<geometry>
<box size="${length_x} ${length_y} ${length_z}"/>
</geometry>
</collision>
<inertial>
<mass value="${mass}" />
<xacro:insert_block name="origin"/>
<inertia
ixx="${(1/12) * mass * (length_y*length_y + length_z*length_z)}"
ixy="0.0"
ixz="0.0"
iyy="${(1/12) * mass * (length_x*length_x + length_z*length_z)}"
iyz="0.0"
izz="${(1/12) * mass * (length_x*length_x + length_y*length_y)}" />
</inertial>
</link>
</xacro:macro>
<!-- Lidar sensor -->
<xacro:macro name="sensor_lidar" params="name parent_link chassis_top_relative_height">
<xacro:property name="mass" value="0.17"/>
<xacro:property name="length_x" value="0.071" />
<xacro:property name="length_y" value="0.10" />
<xacro:property name="length_z" value="0.06" />
<xacro:property name="collision_x_offset" value="0" />
<xacro:property name="collision_y_offset" value="0" />
<xacro:property name="collision_z_offset" value="${chassis_top_relative_height}" />
<joint name="joint_body_to_sensor_lidar_${name}" type="fixed">
<parent link="${parent_link}"/>
<child link="link_sensor_lidar_${name}"/>
<origin rpy="0 0 0" xyz="${collision_x_offset} ${collision_y_offset} ${collision_z_offset}"/>
</joint>
<link name="link_sensor_lidar_${name}">
<visual>
<origin rpy="0 0 0" xyz="0.0 0 ${0.5 * length_z}"/>
<geometry>
<box size="${length_x} ${length_y} ${length_z}"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.0 0 ${0.5 * length_z}"/>
<geometry>
<box size="${length_x} ${length_y} ${length_z}"/>
</geometry>
</collision>
<inertial>
<mass value="${mass}" />
<origin rpy="0 0 0" xyz="0.0 0 ${0.5 * length_z}"/>
<inertia
ixx="${(1/12) * mass * (length_y*length_y + length_z*length_z)}"
ixy="0.0"
ixz="0.0"
iyy="${(1/12) * mass * (length_x*length_x + length_z*length_z)}"
iyz="0.0"
izz="${(1/12) * mass * (length_x*length_x + length_y*length_y)}" />
</inertial>
</link>
</xacro:macro>
<!-- Bump sensor -->
<!-- Sonar sensor -->
<!-- IR sensor -->
</robot>