model.sdf
1.84 KB
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
<?xml version="1.0" ?>
<sdf version="1.4">
<model name="lidar">
<link name="link">
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.01</mass>
<inertia>
<ixx>2.1733e-6</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>2.1733e-6</iyy>
<iyz>0</iyz>
<izz>1.8e-7</izz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<cylinder><radius>0.006</radius><length>0.05</length></cylinder>
</geometry>
<material>
<script>
<name>Gazebo/Black</name>
</script>
</material>
</visual>
<sensor name="laser" type="ray">
<pose>0 0 0 0 1.57079633 0</pose>
<ray>
<scan>
<horizontal>
<samples>1</samples>
<resolution>1</resolution>
<min_angle>-0</min_angle>
<max_angle>0</max_angle>
</horizontal>
</scan>
<range>
<min>0.06</min> <!-- do not change: use min_distance (below) for realistic behavior (smaller values cause issues) -->
<max>35</max> <!-- do not change: use min_distance (below) for realistic behavior (bigger values cause issues) -->
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.02</stddev>
</noise>
</ray>
<plugin name="LaserPlugin" filename="libgazebo_lidar_plugin.so">
<robotNamespace></robotNamespace>
<min_distance>0.2</min_distance>
<max_distance>15.0</max_distance>
</plugin>
<always_on>1</always_on>
<update_rate>20</update_rate>
<visualize>true</visualize>
</sensor>
</link>
</model>
</sdf>