Skip to content

Commit

Permalink
Label Component & System, segmentation camera support (#853)
Browse files Browse the repository at this point in the history
Signed-off-by: AmrElsersy <amrelsersay@gmail.com>
Signed-off-by: Ashton Larkin <ashton@openrobotics.org>

Co-authored-by: Ashton Larkin <ashton@openrobotics.org>
Co-authored-by: Louise Poubel <louise@openrobotics.org>
  • Loading branch information
3 people authored Sep 22, 2021
1 parent d889c5f commit 9ecebc1
Show file tree
Hide file tree
Showing 12 changed files with 1,301 additions and 509 deletions.
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -122,6 +122,7 @@ ign_find_package(ignition-sensors6 REQUIRED

# cameras
camera
segmentation_camera
depth_camera
rgbd_camera
thermal_camera
Expand Down
362 changes: 362 additions & 0 deletions examples/worlds/segmentation_camera.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,362 @@
<?xml version="1.0" ?>
<!--
Segmentation camera demo for visualizing the semantic & instance segmentation sensor output
-->
<sdf version="1.6">
<world name="shapes">
<plugin
filename="ignition-gazebo-physics-system"
name="ignition::gazebo::systems::Physics">
</plugin>
<plugin
filename="ignition-gazebo-user-commands-system"
name="ignition::gazebo::systems::UserCommands">
</plugin>
<plugin
filename="ignition-gazebo-scene-broadcaster-system"
name="ignition::gazebo::systems::SceneBroadcaster">
</plugin>
<plugin
filename="ignition-gazebo-sensors-system"
name="ignition::gazebo::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>

<gui fullscreen="0">

<!-- 3D scene -->
<plugin filename="GzScene3D" name="3D View">
<ignition-gui>
<title>3D View</title>
<property type="bool" key="showTitleBar">false</property>
<property type="string" key="state">docked</property>
</ignition-gui>

<engine>ogre</engine>
<scene>scene</scene>
<ambient_light>1.0 1.0 1.0</ambient_light>
<background_color>0.8 0.8 0.8</background_color>
<camera_pose>-6 0 6 0 0.5 0</camera_pose>
</plugin>

<!-- World control -->
<plugin filename="WorldControl" name="World control">
<ignition-gui>
<title>World control</title>
<property type="bool" key="showTitleBar">false</property>
<property type="bool" key="resizable">false</property>
<property type="double" key="height">72</property>
<property type="double" key="width">121</property>
<property type="double" key="z">1</property>

<property type="string" key="state">floating</property>
<anchors target="3D View">
<line own="left" target="left"/>
<line own="bottom" target="bottom"/>
</anchors>
</ignition-gui>

<play_pause>true</play_pause>
<step>true</step>
<start_paused>true</start_paused>

</plugin>

<!-- World statistics -->
<plugin filename="WorldStats" name="World stats">
<ignition-gui>
<title>World stats</title>
<property type="bool" key="showTitleBar">false</property>
<property type="bool" key="resizable">false</property>
<property type="double" key="height">110</property>
<property type="double" key="width">290</property>
<property type="double" key="z">1</property>

<property type="string" key="state">floating</property>
<anchors target="3D View">
<line own="right" target="right"/>
<line own="bottom" target="bottom"/>
</anchors>
</ignition-gui>

<sim_time>true</sim_time>
<real_time>true</real_time>
<real_time_factor>true</real_time_factor>
<iterations>true</iterations>
</plugin>

<!-- Image Display Plugins for visualization -->
<plugin filename="ImageDisplay" name="Image Display">
<ignition-gui>
</ignition-gui>
<topic>semantic/colored_map</topic>
</plugin>
<plugin filename="ImageDisplay" name="Image Display">
<ignition-gui>
</ignition-gui>
<topic>panoptic/colored_map</topic>
</plugin>
<plugin filename="ImageDisplay" name="Image Display">
<ignition-gui>
</ignition-gui>
<topic>semantic/labels_map</topic>
</plugin>
</gui>

<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>

<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
</link>
</model>

<!-- Cars, all of them have label 40 -->
<include>
<name>Car1</name>
<pose>-2 -2 0 0 0 0</pose>
<uri>
https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Hatchback blue
</uri>
<plugin filename="ignition-gazebo-label-system" name="ignition::gazebo::systems::Label">
<label>40</label>
</plugin>
</include>

<include>
<name>Car2</name>
<pose>-3 -5 0 0 0 0</pose>
<uri>
https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Pickup
</uri>
<plugin filename="ignition-gazebo-label-system" name="ignition::gazebo::systems::Label">
<label>40</label>
</plugin>
</include>

<include>
<name>Car3</name>
<pose>-4 3 0 0 0 -1.57</pose>
<uri>
https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/SUV
</uri>
<plugin filename="ignition-gazebo-label-system" name="ignition::gazebo::systems::Label">
<label>40</label>
</plugin>
</include>

<!-- Tree, all of them have label 30 -->
<include>
<name>tree1</name>
<pose>-2 5 0 0 0 0</pose>
<uri>
https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Pine Tree
</uri>
<plugin filename="ignition-gazebo-label-system" name="ignition::gazebo::systems::Label">
<label>30</label>
</plugin>
</include>

<include>
<name>tree2</name>
<pose>-7 2 0 0 0 0</pose>
<uri>
https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Pine Tree
</uri>
<plugin filename="ignition-gazebo-label-system" name="ignition::gazebo::systems::Label">
<label>30</label>
</plugin>
</include>

<include>
<name>tree3</name>
<pose>-7 -4 0 0 0 0</pose>
<uri>
https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Pine Tree
</uri>
<plugin filename="ignition-gazebo-label-system" name="ignition::gazebo::systems::Label">
<label>30</label>
</plugin>
</include>

<!-- Home, we didn't annotate (label) it, so it will be considered as background -->
<include>
<name>home</name>
<pose>-15 0 0 0 0 1.57</pose>
<uri>
https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Collapsed House
</uri>
</include>

<!-- Cones, all with label 20-->
<include>
<name>cone1</name>
<pose>0 1 0 0 0 1.570796</pose>
<uri>
https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Construction Cone
</uri>
<plugin filename="ignition-gazebo-label-system" name="ignition::gazebo::systems::Label">
<label>20</label>
</plugin>
</include>

<include>
<name>cone2</name>
<pose>0 4 0 0 0 1.570796</pose>
<uri>
https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Construction Cone
</uri>
<plugin filename="ignition-gazebo-label-system" name="ignition::gazebo::systems::Label">
<label>20</label>
</plugin>
</include>

<include>
<name>cone3</name>
<pose>2 -2 0 0 0.0 1.57</pose>
<uri>
https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Construction Cone
</uri>
<plugin filename="ignition-gazebo-label-system" name="ignition::gazebo::systems::Label">
<label>20</label>
</plugin>
</include>

<!-- Instance / Panoptic Segmentation Camera Sensor -->
<model name="instance_camera">
<pose>6 0 2.0 0 0.0 3.14</pose>
<link name="link">
<pose>0 0 0 0 0 0</pose>
<inertial>
<mass>0.5</mass>
<inertia>
<ixx>0.000166667</ixx>
<iyy>0.000166667</iyy>
<izz>0.000166667</izz>
</inertia>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.1 0.1 0.1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.1 0.1 0.1</size>
</box>
</geometry>
</visual>

<sensor name="instance_segmentation_camera" type="segmentation">
<topic>panoptic</topic>
<camera>
<segmentation_type>instance</segmentation_type>
<horizontal_fov>1.57</horizontal_fov>
<image>
<width>800</width>
<height>600</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<save enabled="true">
<path>segmentation_data/instance_camera</path>
</save>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>true</visualize>
</sensor>
</link>
</model>

<!-- Semantic Segmentation Camera Sensor -->
<model name="semantic_camera">
<pose>6 0 2.0 0 0.0 3.14</pose>
<link name="link">
<pose>0 0 0 0 0 0</pose>
<inertial>
<mass>0.5</mass>
<inertia>
<ixx>0.000166667</ixx>
<iyy>0.000166667</iyy>
<izz>0.000166667</izz>
</inertia>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.1 0.1 0.1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.1 0.1 0.1</size>
</box>
</geometry>
</visual>
<sensor name="semantic_segmentation_camera" type="segmentation">
<topic>semantic</topic>
<camera>
<segmentation_type>semantic</segmentation_type>
<horizontal_fov>1.57</horizontal_fov>
<image>
<width>800</width>
<height>600</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<save enabled="true">
<path>segmentation_data/semantic_camera</path>
</save>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>true</visualize>
</sensor>
</link>
</model>

</world>
</sdf>
Loading

0 comments on commit 9ecebc1

Please sign in to comment.