-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathlidar.world
143 lines (122 loc) · 4.45 KB
/
lidar.world
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
<?xml version="1.0" ?>
<sdf version="1.5">
<world name="default">
<!-- A global light source -->
<include>
<uri>model://sun</uri>
</include>
<!-- A ground plane -->
<include>
<uri>model://ground_plane</uri>
</include>
<model name="velodyne_hdl-32">
<!-- Give the base link a unique name -->
<link name="base">
<!-- Offset the base by half the lenght of the cylinder -->
<pose>0 0 0.029335 0 0 0</pose>
<collision name="base_collision">
<geometry>
<cylinder>
<!-- Radius and length provided by Velodyne -->
<radius>.04267</radius>
<length>.05867</length>
</cylinder>
</geometry>
</collision>
<!-- The visual is mostly a copy of the collision -->
<visual name="base_visual">
<geometry>
<cylinder>
<radius>.04267</radius>
<length>.05867</length>
</cylinder>
</geometry>
</visual>
</link>
<!-- Give the base link a unique name -->
<link name="top">
<!-- Add a ray sensor, and give it a name -->
<sensor type="ray" name="sensor">
<!-- Position the ray sensor based on the specification. Also rotate
it by 90 degrees around the X-axis so that the <horizontal> rays
become vertical -->
<pose>0 0 -0.004645 1.5707 0 0</pose>
<!-- Enable visualization to see the rays in the GUI -->
<visualize>true</visualize>
<!-- Set the update rate of the sensor -->
<update_rate>30</update_rate>
<ray>
<!-- The scan element contains the horizontal and vertical beams.
We are leaving out the vertical beams for this tutorial. -->
<scan>
<!-- The horizontal beams -->
<horizontal>
<!-- The velodyne has 32 beams(samples) -->
<samples>32</samples>
<!-- Resolution is multiplied by samples to determine number of
simulated beams vs interpolated beams. See:
http://sdformat.org/spec?ver=1.6&elem=sensor#horizontal_resolution
-->
<resolution>1</resolution>
<!-- Minimum angle in radians -->
<min_angle>-0.53529248</min_angle>
<!-- Maximum angle in radians -->
<max_angle>0.18622663</max_angle>
</horizontal>
</scan>
<!-- Range defines characteristics of an individual beam -->
<range>
<!-- Minimum distance of the beam -->
<min>0.05</min>
<!-- Maximum distance of the beam -->
<max>70</max>
<!-- Linear resolution of the beam -->
<resolution>0.02</resolution>
</range>
</ray>
</sensor>
<!-- Vertically offset the top cylinder by the length of the bottom
cylinder and half the length of this cylinder. -->
<pose>0 0 0.095455 0 0 0</pose>
<collision name="top_collision">
<geometry>
<cylinder>
<!-- Radius and length provided by Velodyne -->
<radius>0.04267</radius>
<length>0.07357</length>
</cylinder>
</geometry>
</collision>
<!-- The visual is mostly a copy of the collision -->
<visual name="top_visual">
<geometry>
<cylinder>
<radius>0.04267</radius>
<length>0.07357</length>
</cylinder>
</geometry>
</visual>
</link>
<!-- Each joint must have a unique name -->
<joint type="revolute" name="joint">
<!-- Position the joint at the bottom of the top link -->
<pose>0 0 -0.036785 0 0 0</pose>
<!-- Use the base link as the parent of the joint -->
<parent>base</parent>
<!-- Use the top link as the child of the joint -->
<child>top</child>
<!-- The axis defines the joint's degree of freedom -->
<axis>
<!-- Revolve around the z-axis -->
<xyz>0 0 1</xyz>
<!-- Limit refers to the range of motion of the joint -->
<limit>
<!-- Use a very large number to indicate a continuous revolution -->
<lower>-10000000000000000</lower>
<upper>10000000000000000</upper>
</limit>
</axis>
</joint>
</model>
</world>
</sdf>