-
Notifications
You must be signed in to change notification settings - Fork 228
/
autoRallyPlatform.urdf.xacro
670 lines (591 loc) · 24.4 KB
/
autoRallyPlatform.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
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
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
<?xml version="1.0"?>
<!-- autoRallyPlatform.urdf.xacro
This file defines a model of the AutoRally autonomous vehicle platform. It is
derived from the ackermann_vehicle_gazebo ROS package available at
http://wiki.ros.org/ackermann_vehicle_gazebo
Lengths are measured in meters, angles are measured in radians, and masses are
measured in kilograms. All of these values are approximations.
To work with Gazebo, each link must have an inertial element, even if
the link only serves to connect two joints. To be visible in Gazebo, a link
must have a collision element. Furthermore, the link must have a Gazebo
material.
Copyright (c) 2011-2014 Wunderkammer Laboratory
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
-->
<robot name="autorally_platform" xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- Degree-to-radian conversions -->
<xacro:property name="degrees_45" value="0.785398163"/>
<xacro:property name="degrees_21" value="0.3665191429"/>
<xacro:property name="degrees_90" value="1.57079633"/>
<!-- chassis_length is measured along the x axis, chassis_width
along the y axis, and chassis_height along the z axis. -->
<xacro:property name="chassis_length" value="0.90"/>
<xacro:property name="chassis_width" value="0.25"/>
<xacro:property name="chassis_height" value="0.25"/>
<xacro:property name="chassis_mass" value="20.5"/>
<xacro:property name="chassis_cm_height" value="0.12"/>
<xacro:property name="chassis_cm_to_rear_shock" value="0.23"/>
<xacro:property name="chassis_cm_to_front_shock" value="0.34"/>
<!-- hub_dia and tire_dia are the diameters of the hub and tire,
respectively. hex_hub_depth is the distance that the hex hub is
inset from the outer edge of the tire. It is set so that each wheel
is a "zero offset" wheel. hex_hub_depth = tire_width / 2 -
axle_length. -->
<xacro:property name="hub_dia" value="0.024"/>
<xacro:property name="tire_dia" value="0.19"/>
<!-- <xacro:property name="hex_hub_depth" value="0.0"/> -->
<xacro:property name="front_tire_width" value="0.072644"/>
<xacro:property name="front_wheel_mass" value="0.82"/>
<xacro:property name="rear_tire_width" value="0.0762"/>
<xacro:property name="rear_wheel_mass" value="0.89"/>
<!-- hex_hub_dist is the distance between left and right hex hubs when
the shock absorbers are fully extended. axle_length is the distance
from a U joint to the corresponding hex hub. wheel_travel is the
vertical wheel travel. -->
<xacro:property name="wheelbase" value="0.570"/>
<xacro:property name="hex_hub_dist" value="0.4"/>
<!-- <xacro:property name="axle_length" value="0.03"/> -->
<!--<xacro:property name="wheel_travel" value="0.1"/>
<xacro:property name="shock_z_offset" value="0.11"/> -->
<xacro:property name="front_wheel_travel" value="0.1"/>
<xacro:property name="front_shock_z_offset" value="0.11"/>
<xacro:property name="rear_wheel_travel" value="0.11"/>
<xacro:property name="rear_shock_z_offset" value="0.12"/>
<!-- shock_eff_limit is 2 * ((shock_stroke / 2) * shock_spring_constant) N.
For shock_spring_constants, refer to
autoRallyPlatformJointCtrlrParams.yaml for spring's constants -->
<!-- front shock: 2 * ((0.06 / 2) * 3152.28303) = 189.1369818-->
<!-- rear shock: 2 * ((0.07 / 2) * 4234.88528273) = 296.441969791-->
<xacro:property name="front_shock_eff_limit" value="189.1369818"/>
<xacro:property name="rear_shock_eff_limit" value="296.441969791"/>
<xacro:property name="shock_vel_limit" value="1000"/>
<!-- The specifications for a Titan(R) 550 motor could not be found, so the
stall torque of a Mabuchi Motor(R) RS-550VC-7525 motor was used instead.
num_spur_gear_teeth = 68
num_pinion_gear_teeth = 19
final_gear_ratio = (num_spur_gear_teeth / num_pinion_gear_teeth) *
5.22 = 18.68
stall_torque = 0.549 N m
axle_eff_limit = ((2 * stall_torque) * final_gear_ratio) / 4 =
5.12766 N m
max_speed = 60mph = 26.82 m/s
axle_vel_limit = (2 * pi) * (max_speed / (pi * tire_dia)) =
2*26.82/0.19 = 282.315789474 rad/s
-->
<xacro:property name="front_axle_eff_limit" value="2"/>
<xacro:property name="rear_axle_eff_limit" value="8"/>
<xacro:property name="axle_vel_limit" value="282.315789474"/>
<!-- These constants are used to simulate a Savox SV-0235MG servo operated at
7.4 V. servo_stall_torque is measured in N m. servo_no_load_speed is
measured in rad/s. -->
<!-- produces 486.1 oz-in = 3.432620346181713 n-m of torque -->
<!-- no load speed 0.13 sec/60 deg -> (1/0.13)*60 deg/sec = 8.05536578 rad/s -->
<xacro:property name="servo_stall_torque" value="3.432620346181713"/>
<xacro:property name="servo_no_load_speed" value="8.05536578"/>
<material name="chassis_mat">
<color rgba="0.5 0.5 0.5 1"/>
</material>
<!-- Null inertial element. This is needed to make the model work with
Gazebo. -->
<xacro:macro name="null_inertial">
<inertial>
<mass value="0.001"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
</xacro:macro>
<!-- Inertia of a thick-walled cylindrical tube with open ends. Height is
measured along the z axis, which is the tube's axis. inner_rad and
outer_rad are the tube's inner and outer radii, respectively. Pitch
MOI is calculated from platform calibration data using bifilar pendulum
method -->
<xacro:macro name="thick_walled_tube_inertial"
params="inner_rad outer_rad height mass">
<inertial>
<mass value="${mass}"/>
<inertia ixx="${(1 / 12) * mass * (3 * (inner_rad * inner_rad +
outer_rad * outer_rad) + height * height)}"
ixy="0" ixz="0"
iyy="0.0224048079"
iyz="0"
izz="${mass * (inner_rad * inner_rad +
outer_rad * outer_rad) / 2}"/>
</inertial>
</xacro:macro>
<!-- Shock absorbers -->
<xacro:macro name="front_shock"
params="lr_prefix fr_prefix lr_reflect fr_reflect child">
<joint name="${lr_prefix}_${fr_prefix}_shock" type="prismatic">
<parent link="chassis"/>
<child link="${child}"/>
<!-- ${lr_reflect * ((hex_hub_dist / 2) + lr_reflect*(front_tire_width / 2))} -->
<origin xyz="${fr_reflect * chassis_cm_to_front_shock}
${lr_reflect * ((hex_hub_dist / 2) - 0.01)}
${-chassis_cm_height + front_shock_z_offset/2}"/>
<axis xyz="0 0 -1"/>
<limit lower="${-front_wheel_travel / 2}" upper="${front_wheel_travel / 2}"
effort="${front_shock_eff_limit}" velocity="${shock_vel_limit}"/>
<dynamics damping="88" friction="0.0001"
spring_stiffness="3152" spring_reference="0.08"/>
</joint>
<transmission name="${lr_prefix}_${fr_prefix}_shock_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${lr_prefix}_${fr_prefix}_shock">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${lr_prefix}_${fr_prefix}_shock_act">
<!-- This hardwareInterface element exists for compatibility
with ROS Hydro. -->
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro>
<xacro:macro name="rear_shock"
params="lr_prefix fr_prefix lr_reflect fr_reflect child">
<joint name="${lr_prefix}_${fr_prefix}_shock" type="prismatic">
<parent link="chassis"/>
<child link="${child}"/>
<!-- ${lr_reflect * ((hex_hub_dist / 2) + lr_reflect*(front_tire_width / 2))} -->
<origin xyz="${fr_reflect * chassis_cm_to_rear_shock}
${lr_reflect * ((hex_hub_dist / 2) )}
${-chassis_height/2 + rear_shock_z_offset/2}"/>
<axis xyz="0 0 -1"/>
<limit lower="${-rear_wheel_travel / 2}" upper="${rear_wheel_travel / 2}"
effort="${rear_shock_eff_limit}" velocity="${shock_vel_limit}"/>
<dynamics damping="88" friction="0.0"/>
</joint>
<transmission name="${lr_prefix}_${fr_prefix}_shock_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${lr_prefix}_${fr_prefix}_shock">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${lr_prefix}_${fr_prefix}_shock_act">
<!-- This hardwareInterface element exists for compatibility
with ROS Hydro. -->
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro>
<!-- The "wheel" macro defines an axle carrier, axle, and wheel. -->
<xacro:macro name="wheel" params="lr_prefix fr_prefix lr_reflect tire_width wheel_mass axle_eff_limit wheel_model cant">
<link name="${lr_prefix}_${fr_prefix}_axle_carrier">
<xacro:null_inertial/>
</link>
<!-- The left and right axles have the same axis so that identical
rotation values cause the wheels to rotate in the same direction. -->
<joint name="${lr_prefix}_${fr_prefix}_axle" type="continuous">
<parent link="${lr_prefix}_${fr_prefix}_axle_carrier"/>
<child link="${lr_prefix}_${fr_prefix}_wheel"/>
<origin xyz="0 0 0" rpy="${degrees_90} 0 0"/>
<axis xyz="0 0 -1"/>
<limit effort="${axle_eff_limit}" velocity="${axle_vel_limit}"/>
<!-- <dynamics damping="0.015" friction="0.0"/> -->
<dynamics damping="0.001" friction="0.5"/>
</joint>
<!-- <gazebo reference="${lr_prefix}_${fr_prefix}_axle">
<dampingFactor>0.8</dampingFactor>
</gazebo>
-->
<transmission name="${lr_prefix}_${fr_prefix}_axle_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${lr_prefix}_${fr_prefix}_axle">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${lr_prefix}_${fr_prefix}_axle_act">
<!-- This hardwareInterface element exists for compatibility
with ROS Hydro. -->
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<link name="${lr_prefix}_${fr_prefix}_wheel">
<visual>
<origin xyz="0 0 0"/>
<geometry>
<mesh filename="${wheel_model}" />
</geometry>
</visual>
<collision name="collision">
<origin xyz="0 0 0"/>
<geometry>
<mesh filename="${wheel_model}" />
</geometry>
</collision>
<collision name="material">
<origin xyz="0 0 0"/>
<geometry>
<mesh filename="${wheel_model}" />
</geometry>
</collision>
<xacro:thick_walled_tube_inertial
inner_rad="${hub_dia / 2.0}" outer_rad="${tire_dia / 2.0}"
height="${tire_width}" mass="${wheel_mass}"/>
<max_contacts>1</max_contacts>
<surface>
<contact>
<ode>
<soft_cfm>0.000000001</soft_cfm>
<soft_erp>0.2</soft_erp>
<kp>1e+10</kp>
<kd>10</kd>
<max_vel>0.01</max_vel>
<min_depth>0.005</min_depth>
</ode>
</contact>
</surface>
</link>
<gazebo reference="${lr_prefix}_${fr_prefix}_wheel">
<mu1>0.7</mu1>
<mu2>0.75</mu2>
</gazebo>
</xacro:macro>
<!-- Front wheel -->
<xacro:macro name="front_wheel"
params="lr_prefix fr_prefix lr_reflect fr_reflect tire_width
wheel_mass axle_eff_limit">
<xacro:front_shock lr_prefix="${lr_prefix}" fr_prefix="${fr_prefix}"
lr_reflect="${lr_reflect}" fr_reflect="${fr_reflect}"
child="${lr_prefix}_steering_link"/>
<link name="${lr_prefix}_steering_link">
<xacro:null_inertial/>
</link>
<joint name="${lr_prefix}_steering_joint" type="revolute">
<parent link="${lr_prefix}_steering_link"/>
<child link="${lr_prefix}_${fr_prefix}_axle_carrier"/>
<!-- cant the front wheels to improve traction -->
<axis xyz="0 ${-lr_reflect*0.09950372} 0.99503719"/>
<limit lower="${-degrees_21}" upper="${degrees_21}"
effort="${servo_stall_torque}" velocity="${servo_no_load_speed}"/>
</joint>
<transmission name="${lr_prefix}_steering_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${lr_prefix}_steering_joint">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${lr_prefix}_steering_act">
<!-- This hardwareInterface element exists for compatibility
with ROS Hydro. -->
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<xacro:wheel lr_prefix="${lr_prefix}" fr_prefix="${fr_prefix}"
lr_reflect="${lr_reflect}" tire_width="${tire_width}"
wheel_mass="${wheel_mass}"
axle_eff_limit="${axle_eff_limit}"
wheel_model="package://autorally_description/urdf/autoRallyPlatformFrontWheelTextured.dae"
cant="0.05"/>
</xacro:macro>
<!-- Rear wheel -->
<xacro:macro name="rear_wheel"
params="lr_prefix fr_prefix lr_reflect fr_reflect tire_width
wheel_mass axle_eff_limit">
<xacro:rear_shock lr_prefix="${lr_prefix}" fr_prefix="${fr_prefix}"
lr_reflect="${lr_reflect}" fr_reflect="${fr_reflect}"
child="${lr_prefix}_${fr_prefix}_axle_carrier"/>
<xacro:wheel lr_prefix="${lr_prefix}" fr_prefix="${fr_prefix}"
lr_reflect="${lr_reflect}" tire_width="${tire_width}"
wheel_mass="${wheel_mass}"
axle_eff_limit="${axle_eff_limit}"
wheel_model="package://autorally_description/urdf/autoRallyPlatformRearWheelTextured.dae"
cant="-0.03"/>
</xacro:macro>
<!-- base_link must have geometry so that its axes can be displayed in
rviz. -->
<link name="base_link">
<visual>
<geometry>
<box size="0.01 0.01 0.01"/>
</geometry>
<material name="chassis_mat"/>
</visual>
</link>
<gazebo reference="base_link">
<material>Gazebo/Grey</material>
</gazebo>
<!-- Chassis -->
<link name="chassis">
<visual>
<origin xyz="${-chassis_length/2 + 0.15} 0 ${-chassis_cm_height}"
rpy="0 0 0"/>
<geometry>
<mesh filename="package://autorally_description/urdf/Vehicle_Texture.dae" scale="1 1 1" />
</geometry>
</visual>
<collision>
<origin xyz="${-chassis_length/2 + 0.2} 0 ${-chassis_cm_height}"
rpy="0 0 0"/>
<geometry>
<mesh filename="package://autorally_description/urdf/Vehicle_Texture.dae" scale="1 1 1" />
</geometry>
</collision>
<inertial>
<mass value="${chassis_mass}"/>
<inertia ixx="0.003881755275"
ixy="0" ixz="0"
iyy="0.011310597718"
iyz="0"
izz="0.01243832479"/>
</inertial>
</link>
<gazebo reference="chassis">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<joint name="base_link_to_chasis" type="fixed">
<axis xyz="0 -1 -1" />
<parent link="base_link"/>
<child link="chassis"/>
</joint>
<link name="imu_link">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.1 0.1"/>
</geometry>
</collision>
<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>
<joint name="imu_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="imu_link"/>
</joint>
<joint name="camera_joint" type="fixed">
<axis xyz="0 0 -1" />
<origin xyz="0.12 0 0.05" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="camera_link"/>
</joint>
<!-- Camera -->
<link name="camera_link">
<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>
<joint name="side_camera_joint" type="fixed">
<axis xyz="0 1 0" />
<origin xyz="0 -3 0" rpy="0 0 1.5708"/>
<parent link="base_link"/>
<child link="side_camera_link"/>
</joint>
<!-- Camera -->
<link name="side_camera_link">
<!-- <collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.05 0.05 0.05"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.05 0.05 0.05"/>
</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 -->
<gazebo reference="camera_link">
<sensor type="multicamera" name="stereo_camera">
<update_rate>30.0</update_rate>
<camera name="left">
<pose>0 0.07 0 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1280</width>
<height>1024</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.009</stddev>
</noise>
</camera>
<camera name="right">
<pose>0.02 -0.07 0 0 0 0</pose>
<horizontal_fov>3.0</horizontal_fov>
<image>
<width>1280</width>
<height>1024</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.009</stddev>
</noise>
</camera>
<plugin name="stereo_camera_controller" filename="libgazebo_ros_multicamera.so">
<alwaysOn>true</alwaysOn>
<updateRate>60.0</updateRate>
<cameraName>camera</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>left_camera_optical_frame</frameName>
<!--<rightFrameName>right_camera_optical_frame</rightFrameName>-->
<hackBaseline>0.14</hackBaseline>
<!-- <distortionK1>-0.212652</distortionK1>
<distortionK2>0.085434</distortionK2>
<distortionK3>-0.000165</distortionK3>
<distortionT1>-0.000336</distortionT1>
<distortionT2>0.0</distortionT2> -->
</plugin>
</sensor>
</gazebo>
<!-- camera -->
<gazebo reference="side_camera_link">
<sensor type="camera" name="camera_side">
<update_rate>30.0</update_rate>
<camera name="side">
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1280</width>
<height>1024</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>50</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>camera_side</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>side_camera_link</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>
<!-- Wheels -->
<xacro:front_wheel lr_prefix="left" fr_prefix="front"
lr_reflect="1" fr_reflect="1"
tire_width="${front_tire_width}"
wheel_mass="${front_wheel_mass}"
axle_eff_limit="${front_axle_eff_limit}"/>
<xacro:front_wheel lr_prefix="right" fr_prefix="front"
lr_reflect="-1" fr_reflect="1"
tire_width="${front_tire_width}"
wheel_mass="${front_wheel_mass}"
axle_eff_limit="${front_axle_eff_limit}"/>
<xacro:rear_wheel lr_prefix="left" fr_prefix="rear"
lr_reflect="1" fr_reflect="-1"
tire_width="${rear_tire_width}"
wheel_mass="${rear_wheel_mass}"
axle_eff_limit="${rear_axle_eff_limit}"/>
<xacro:rear_wheel lr_prefix="right" fr_prefix="rear"
lr_reflect="-1" fr_reflect="-1"
tire_width="${rear_tire_width}"
wheel_mass="${rear_wheel_mass}"
axle_eff_limit="${rear_axle_eff_limit}"/>
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/autorally_platform</robotNamespace>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
</plugin>
<plugin name="imu" filename="libhector_gazebo_ros_imu.so">
<robotNamespace>/autorally_platform</robotNamespace>
<serviceName>/imu/calibrate</serviceName>
<updateRate>200.0</updateRate>
<bodyName>imu_link</bodyName>
<frameId>imu_link</frameId>
<topicName>imu</topicName>
<rpyOffset>0 0 0</rpyOffset>
<xyzOffset>0 0 0</xyzOffset>
<gaussianNoise>0.00000001</gaussianNoise>
<accelDrift>0.00000001 0.00000001 0.00000001</accelDrift>
<accelDriftFrequency>0.00000001 0.00000001 0.00000001</accelDriftFrequency>
<accelGaussianNoise>0.00000001 0.00000001 0.00000001</accelGaussianNoise>
<rateDrift>0.0 0.0 0.0</rateDrift>
<rateDriftFrequency>0.0 0.0 0.0</rateDriftFrequency>
<rateGaussianNoise>0.0 0.0 0.0</rateGaussianNoise>
<headingDrift>0.0 0.0 0.0</headingDrift>
<headingDriftFrequency>0.0 0.0 0.0</headingDriftFrequency>
<headingGaussianNoise>0.0 0.0 0.0</headingGaussianNoise>
</plugin>
<plugin name="gps" filename="libhector_gazebo_ros_gps.so">
<updateRate>20.0</updateRate>
<bodyName>base_link</bodyName>
<frameId>base_link</frameId>
<topicName>gpsRoverStatus</topicName>
<velocityTopicName>fix_velocity</velocityTopicName>
<referenceLatitude>33.774497</referenceLatitude>
<referenceLongitude>-84.405001</referenceLongitude>
<referenceAltitude>309.0</referenceAltitude>
<drift>0.001 0.001 0.001</drift>
<gaussianNoise>0.0001 0.0001 0.0001</gaussianNoise>
<velocityDrift>0 0 0</velocityDrift>
<velocityGaussianNoise>0.005 0.005 0.05</velocityGaussianNoise>
</plugin>
<!-- <plugin name="tire_friction" filename="libTireFrictionPlugin.so">
<link_name>left_rear_wheel</link_name>
<collision_name>collision</collision_name>
<friction_static>1.1</friction_static>
<friction_dynamic>0.7</friction_dynamic>
<slip_static>0.10</slip_static>
<slip_dynamic>0.20</slip_dynamic>
<speed_static>0.50</speed_static>
</plugin> -->
</gazebo>
</robot>