-
Notifications
You must be signed in to change notification settings - Fork 766
/
gazebo_ros_ray_sensor_demo.world
238 lines (219 loc) · 6.91 KB
/
gazebo_ros_ray_sensor_demo.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
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
<?xml version="1.0" encoding="UTF-8"?>
<!--
Gazebo ROS Ray Sensor plugin demo
To run:
gazebo gazebo_ros_ray_sensor_demo.world
Then open RVIZ:
ros2 run rviz2 rviz2
On RViz, add the following topics:
* /ray/pointcloud2
* /ray/pointcloud
* /ray/laserscan
* /gpu_ray/pointcloud2
* /gpu_ray/pointcloud
* /gpu_ray/laserscan
(Note that the laser scans are not working on RViz due to https://github.com/ros2/rviz/issues/332)
On RViz, change the "Fixed Frame" to `ray_link`
Echo the range topics, i.e.
ros2 topic echo /ray/range
ros2 topic echo /gpu_ray/range
-->
<sdf version="1.6">
<world name="ray_sensor_demo">
<gravity>0 0 0</gravity>
<include>
<uri>model://sun</uri>
</include>
<model name="ray_sensor_box">
<pose>-1.5 0.0 0.0 0.0 0.0 0.0</pose>
<link name="ray_link">
<visual name="visual_box">
<geometry>
<box>
<size>0.05 0.05 0.05</size>
</box>
</geometry>
</visual>
<collision name="collision_box">
<geometry>
<box>
<size>0.05 0.05 0.05</size>
</box>
</geometry>
<laser_retro>100.0</laser_retro>
</collision>
<!-- ray sensor -->
<sensor name="sensor_ray" type="ray">
<ray>
<scan>
<horizontal>
<samples>300</samples>
<resolution>1.0</resolution>
<min_angle>-0.5236</min_angle>
<max_angle>0.5236</max_angle>
</horizontal>
<vertical>
<samples>100</samples>
<resolution>1.0</resolution>
<min_angle>-0.5236</min_angle>
<max_angle>0.5236</max_angle>
</vertical>
</scan>
<range>
<min>0.05</min>
<max>50.0</max>
</range>
</ray>
<always_on>true</always_on>
<update_rate>1.0</update_rate>
<plugin name="pc2" filename="libgazebo_ros_ray_sensor.so">
<ros>
<namespace>/ray</namespace>
<argument>~/out:=pointcloud2</argument>
</ros>
<output_type>sensor_msgs/PointCloud2</output_type>
</plugin>
<plugin name="pc" filename="libgazebo_ros_ray_sensor.so">
<ros>
<namespace>/ray</namespace>
<argument>~/out:=pointcloud</argument>
</ros>
<output_type>sensor_msgs/PointCloud</output_type>
</plugin>
<plugin name="laserscan" filename="libgazebo_ros_ray_sensor.so">
<ros>
<namespace>/ray</namespace>
<argument>~/out:=laserscan</argument>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
</plugin>
<plugin name="range" filename="libgazebo_ros_ray_sensor.so">
<ros>
<namespace>/ray</namespace>
<argument>~/out:=range</argument>
</ros>
<output_type>sensor_msgs/Range</output_type>
</plugin>
</sensor>
<!-- gpu_ray sensor producing PointCloud / LaserScan -->
<sensor name="sensor_gpu_ray" type="gpu_ray">
<ray>
<scan>
<horizontal>
<samples>300</samples>
<resolution>1.0</resolution>
<min_angle>-0.5236</min_angle>
<max_angle>0.5236</max_angle>
</horizontal>
<!--
gpu_ray currently only supports 1 vertical ray (no vertical tag)
See https://bitbucket.org/osrf/gazebo/issues/2486
<vertical>
<samples>100</samples>
<resolution>1.0</resolution>
<min_angle>-0.5236</min_angle>
<max_angle>0.5236</max_angle>
</vertical-->
</scan>
<range>
<min>0.05</min>
<max>50.0</max>
</range>
</ray>
<always_on>true</always_on>
<update_rate>1.0</update_rate>
<plugin name="pc2_gpu" filename="libgazebo_ros_ray_sensor.so">
<ros>
<namespace>/gpu_ray</namespace>
<argument>~/out:=pointcloud2</argument>
</ros>
<output_type>sensor_msgs/PointCloud2</output_type>
</plugin>
<plugin name="pc_gpu" filename="libgazebo_ros_ray_sensor.so">
<ros>
<namespace>/gpu_ray</namespace>
<argument>~/out:=pointcloud</argument>
</ros>
<output_type>sensor_msgs/PointCloud</output_type>
</plugin>
<plugin name="laserscan_gpu" filename="libgazebo_ros_ray_sensor.so">
<ros>
<namespace>/gpu_ray</namespace>
<argument>~/out:=laserscan</argument>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
</plugin>
<plugin name="range_gpu" filename="libgazebo_ros_ray_sensor.so">
<ros>
<namespace>/gpu_ray</namespace>
<argument>~/out:=range</argument>
</ros>
<output_type>sensor_msgs/Range</output_type>
</plugin>
</sensor>
</link>
</model>
<model name="box">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<link name="base_link">
<visual name="visual">
<geometry>
<box>
<size>0.1 0.25 0.5</size>
</box>
</geometry>
</visual>
<collision name="collision">
<geometry>
<box>
<size>0.1 0.25 0.5</size>
</box>
</geometry>
<laser_retro>100.0</laser_retro>
</collision>
</link>
</model>
<model name="sphere">
<pose>0.5 0.5 0.0 0.0 0.0 0.0</pose>
<link name="base_link">
<visual name="visual">
<geometry>
<sphere>
<radius>0.05</radius>
</sphere>
</geometry>
</visual>
<collision name="collision">
<geometry>
<sphere>
<radius>0.05</radius>
</sphere>
</geometry>
<laser_retro>80.0</laser_retro>
</collision>
</link>
</model>
<model name="cylinder">
<pose>0.5 -0.5 0.0 0.0 0.0 0.0</pose>
<link name="base_link">
<visual name="visual">
<geometry>
<cylinder>
<radius>0.05</radius>
<length>0.5</length>
</cylinder>
</geometry>
</visual>
<collision name="collision">
<geometry>
<cylinder>
<radius>0.05</radius>
<length>0.5</length>
</cylinder>
</geometry>
<laser_retro>60.0</laser_retro>
</collision>
</link>
</model>
</world>
</sdf>