Skip to content

Commit b692ae2

Browse files
arjo129iche033azeey
authored
Adds a system which enables exporting occupancy grids. (#2958)
This PR adds a system which exports occupancy grids. Currently its a work in progress. The BFS algorithm seems to not identify when there cannot be any progress made. --------- Signed-off-by: Arjo Chakravarty <arjoc@intrinsic.ai> Signed-off-by: Addisu Z. Taddese <addisu@openrobotics.org> Co-authored-by: Ian Chen <ichen@openrobotics.org> Co-authored-by: Addisu Z. Taddese <addisu@openrobotics.org>
1 parent a503633 commit b692ae2

File tree

7 files changed

+782
-2
lines changed

7 files changed

+782
-2
lines changed

BUILD.bazel

Lines changed: 20 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -821,6 +821,26 @@ gz_sim_system_libraries(
821821
],
822822
)
823823

824+
gz_sim_system_libraries(
825+
srcs = glob(
826+
[
827+
"src/systems/free_space_explorer/**/*.cc",
828+
"src/systems/free_space_explorer/**/*.hh",
829+
],
830+
),
831+
so_lib_name = "gz-sim-free-space_explorer--system.so",
832+
static_lib_name = "gz-sim-free-space-explorer-system-static",
833+
visibility = ["//visibility:public"],
834+
deps = [
835+
":gz-sim",
836+
"@gz-common//graphics",
837+
"@gz-math",
838+
"@gz-msgs//:gzmsgs_cc_proto",
839+
"@gz-plugin//:register",
840+
"@gz-transport",
841+
],
842+
)
843+
824844
gz_sim_system_libraries(
825845
srcs = glob(
826846
[
Lines changed: 183 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,183 @@
1+
<!--
2+
This world demonstrates the FreeSpaceExplorer system plugin.
3+
A lidar will explore the world and generate an occupancy grid.
4+
The occupancy grid will be published as an image on the /scan_image topic.
5+
6+
To start the exploration, run the following command in a new terminal:
7+
gz topic -t /start_exploration -m gz.msgs.Boolean -p 'data: true'
8+
-->
9+
<sdf version="1.6">
10+
<world name="empty">
11+
<gui>
12+
<plugin filename="ImageDisplay" name="Image Display">
13+
<topic>/scan_image</topic>
14+
</plugin>
15+
</gui>
16+
<physics name="1ms" type="ignored">
17+
<max_step_size>0.001</max_step_size>
18+
<real_time_factor>1.0</real_time_factor>
19+
</physics>
20+
<plugin
21+
filename="gz-sim-physics-system"
22+
name="gz::sim::systems::Physics">
23+
</plugin>
24+
<plugin
25+
filename="gz-sim-user-commands-system"
26+
name="gz::sim::systems::UserCommands">
27+
</plugin>
28+
<plugin
29+
filename="gz-sim-scene-broadcaster-system"
30+
name="gz::sim::systems::SceneBroadcaster">
31+
</plugin>
32+
<plugin
33+
filename="gz-sim-contact-system"
34+
name="gz::sim::systems::Contact">
35+
</plugin>
36+
<plugin
37+
filename="gz-sim-sensors-system"
38+
name="gz::sim::systems::Sensors">
39+
<render_engine>ogre2</render_engine>
40+
</plugin>
41+
42+
<light type="directional" name="sun">
43+
<cast_shadows>true</cast_shadows>
44+
<pose>0 0 10 0 0 0</pose>
45+
<diffuse>0.8 0.8 0.8 1</diffuse>
46+
<specular>0.2 0.2 0.2 1</specular>
47+
<attenuation>
48+
<range>1000</range>
49+
<constant>0.9</constant>
50+
<linear>0.01</linear>
51+
<quadratic>0.001</quadratic>
52+
</attenuation>
53+
<direction>-0.5 0.1 -0.9</direction>
54+
</light>
55+
56+
<model name="model_with_lidar">
57+
<pose>-1 -1 0.5 0 0 0</pose>
58+
<link name="link">
59+
<inertial>
60+
<mass>0.1</mass>
61+
<inertia>
62+
<ixx>0.000166667</ixx>
63+
<iyy>0.000166667</iyy>
64+
<izz>0.000166667</izz>
65+
</inertia>
66+
</inertial>
67+
<collision name="collision">
68+
<geometry>
69+
<box>
70+
<size>0.1 0.1 0.1</size>
71+
</box>
72+
</geometry>
73+
</collision>
74+
<visual name="visual">
75+
<geometry>
76+
<box>
77+
<size>0.1 0.1 0.1</size>
78+
</box>
79+
</geometry>
80+
</visual>
81+
82+
<sensor name='gpu_lidar' type='gpu_lidar'>
83+
<topic>scan</topic>
84+
<update_rate>10</update_rate>
85+
<lidar>
86+
<scan>
87+
<horizontal>
88+
<samples>640</samples>
89+
<resolution>1</resolution>
90+
<min_angle>0</min_angle>
91+
<max_angle>6.28</max_angle>
92+
</horizontal>
93+
</scan>
94+
<range>
95+
<min>0.08</min>
96+
<max>9.0</max>
97+
<resolution>0.01</resolution>
98+
</range>
99+
</lidar>
100+
<visualize>true</visualize>
101+
</sensor>
102+
</link>
103+
<static>true</static>
104+
105+
<plugin
106+
filename="gz-sim-free-space-explorer-system"
107+
name="gz::sim::systems::FreeSpaceExplorer">
108+
<lidar_topic>/scan</lidar_topic>
109+
<image_topic>/scan_image</image_topic>
110+
<start_topic>/start_exploration</start_topic>
111+
<width>100</width>
112+
<height>100</height>
113+
<resolution>0.25</resolution>
114+
<sensor_link>link</sensor_link>
115+
</plugin>
116+
</model>
117+
118+
<model name="cube">
119+
<pose>1 1 0.5 0 0 0</pose>
120+
<link name="box_link">
121+
<inertial>
122+
<inertia>
123+
<ixx>0.16666</ixx>
124+
<ixy>0</ixy>
125+
<ixz>0</ixz>
126+
<iyy>0.16666</iyy>
127+
<iyz>0</iyz>
128+
<izz>0.16666</izz>
129+
</inertia>
130+
<mass>1.0</mass>
131+
</inertial>
132+
<collision name="box_collision">
133+
<geometry>
134+
<box>
135+
<size>1 1 1</size>
136+
</box>
137+
</geometry>
138+
</collision>
139+
140+
<visual name="box_visual">
141+
<geometry>
142+
<box>
143+
<size>1 1 1</size>
144+
</box>
145+
</geometry>
146+
<material>
147+
<ambient>1 0 0 1</ambient>
148+
<diffuse>1 0 0 1</diffuse>
149+
<specular>1 0 0 1</specular>
150+
</material>
151+
</visual>
152+
</link>
153+
</model>
154+
155+
<model name="ground_plane">
156+
<static>true</static>
157+
<link name="link">
158+
<collision name="collision">
159+
<geometry>
160+
<plane>
161+
<normal>0 0 1</normal>
162+
<size>100 100</size>
163+
</plane>
164+
</geometry>
165+
</collision>
166+
<visual name="visual">
167+
<geometry>
168+
<plane>
169+
<normal>0 0 1</normal>
170+
<size>100 100</size>
171+
</plane>
172+
</geometry>
173+
<material>
174+
<ambient>0.8 0.8 0.8 1</ambient>
175+
<diffuse>0.8 0.8 0.8 1</diffuse>
176+
<specular>0.8 0.8 0.8 1</specular>
177+
</material>
178+
</visual>
179+
</link>
180+
</model>
181+
182+
</world>
183+
</sdf>

src/gui/plugins/CMakeLists.txt

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -149,14 +149,14 @@ add_subdirectory(playback_scrubber)
149149
add_subdirectory(plot_3d)
150150
add_subdirectory(plotting)
151151
add_subdirectory(resource_spawner)
152-
add_subdirectory(select_entities)
153152
add_subdirectory(scene_manager)
153+
add_subdirectory(select_entities)
154154
add_subdirectory(shapes)
155155
add_subdirectory(spawn)
156156
add_subdirectory(transform_control)
157157
add_subdirectory(video_recorder)
158158
add_subdirectory(view_angle)
159159
add_subdirectory(visualization_capabilities)
160160
add_subdirectory(visualize_contacts)
161-
add_subdirectory(visualize_lidar)
162161
add_subdirectory(visualize_frustum)
162+
add_subdirectory(visualize_lidar)

src/systems/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -104,6 +104,7 @@ add_subdirectory(environment_preload)
104104
add_subdirectory(environmental_sensor_system)
105105
add_subdirectory(follow_actor)
106106
add_subdirectory(force_torque)
107+
add_subdirectory(free_space_explorer)
107108
add_subdirectory(hydrodynamics)
108109
add_subdirectory(imu)
109110
add_subdirectory(joint_controller)
Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
gz_add_system(free-space-explorer
2+
SOURCES
3+
FreeSpaceExplorer.cc
4+
PUBLIC_LINK_LIBS
5+
gz-common::gz-common
6+
gz-math::gz-math
7+
gz-plugin::core
8+
)

0 commit comments

Comments
 (0)