Skip to content

Commit

Permalink
Support loading Projectors (#1979)
Browse files Browse the repository at this point in the history
Updated SdfEntityCreator to create projector entities
Updated rendering component to load and create projector objects in the scene
Updated scene broadcaster to publish scene info projectors
Added conversion function for serializing / deserializing sdf::Projector to / from msgs::Projector

Signed-off-by: Ian Chen <[email protected]>
  • Loading branch information
iche033 authored May 22, 2023
1 parent bb85d05 commit 42c285e
Show file tree
Hide file tree
Showing 18 changed files with 981 additions and 3 deletions.
274 changes: 274 additions & 0 deletions examples/worlds/projector.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,274 @@
<?xml version="1.0" ?>
<!--
Demo world featuring a model with a projector. The model has 3 sensors:
* IR camera left (grayscale)
* IR camera right (grayscale)
* RGB camera (color)
and a projector that projects out a pattern that is only visible to the
left and right IR cameras.
-->
<sdf version="1.7">
<world name="projector">
<physics name="1ms" type="ignored">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<plugin
filename="gz-sim-physics-system"
name="gz::sim::systems::Physics">
</plugin>
<plugin
filename="gz-sim-sensors-system"
name="gz::sim::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
<plugin
filename="gz-sim-user-commands-system"
name="gz::sim::systems::UserCommands">
</plugin>
<plugin
filename="gz-sim-scene-broadcaster-system"
name="gz::sim::systems::SceneBroadcaster">
</plugin>

<scene>
<ambient>1.0 1.0 1.0</ambient>
<background>0.8 0.8 0.8</background>
<grid>true</grid>
</scene>

<gui fullscreen="0">

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

<engine>ogre2</engine>
<scene>scene</scene>
<ambient_light>0.4 0.4 0.4</ambient_light>
<background_color>0.8 0.8 0.8</background_color>
<camera_pose>-6 0 6 0 0.5 0</camera_pose>
</plugin>

<!-- Plugins that add functionality to the scene -->
<plugin filename="EntityContextMenuPlugin" name="Entity context menu">
<gz-gui>
<property key="state" type="string">floating</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="GzSceneManager" name="Scene Manager">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="InteractiveViewControl" name="Interactive view control">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="CameraTracking" name="Camera Tracking">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<!-- World control -->
<plugin filename="WorldControl" name="World control">
<gz-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>
</gz-gui>

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

</plugin>

<!-- World statistics -->
<plugin filename="WorldStats" name="World stats">
<gz-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>
</gz-gui>

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

<plugin filename="ImageDisplay" name="Image Display">
<gz-gui>
<title>IR Camera Left</title>
<property key="state" type="string">floating</property>
<property type="double" key="width">350</property>
<property type="double" key="height">315</property>
</gz-gui>
<topic>IR_camera_left</topic>
<topic_picker>false</topic_picker>
</plugin>
<plugin filename="ImageDisplay" name="Image Display 2">
<gz-gui>
<title>IR Camera Right</title>
<property key="state" type="string">floating</property>
<property type="double" key="width">350</property>
<property type="double" key="height">315</property>
<property type="double" key="x">500</property>
</gz-gui>
<topic>IR_camera_right</topic>
<topic_picker>false</topic_picker>
</plugin>
<plugin filename="ImageDisplay" name="Image Display 3">
<gz-gui>
<title>RGB Camera</title>
<property key="state" type="string">floating</property>
<property type="double" key="width">350</property>
<property type="double" key="height">315</property>
<property type="double" key="y">320</property>
</gz-gui>
<topic>RGB_camera</topic>
<topic_picker>false</topic_picker>
</plugin>

<!-- Inspector -->
<plugin filename="ComponentInspector" name="Component inspector">
<gz-gui>
<property type="string" key="state">docked</property>
</gz-gui>
</plugin>

<!-- Entity tree -->
<plugin filename="EntityTree" name="Entity tree">
<gz-gui>
<property type="string" key="state">docked</property>
</gz-gui>
</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.8 0.8 0.8 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>

<include>
<pose>0 0 5 0.0 1.57 0</pose>
<uri>
https://fuel.gazebosim.org/1.0/OpenRobotics/models/Camera with Projector
</uri>
</include>

<model name="box">
<pose>0 0 0.5 0 0 0</pose>
<link name="box_link">
<inertial>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<collision name="box_collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</collision>

<visual name="box_visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>1 0 0 1</diffuse>
<specular>1 0 0 1</specular>
</material>
</visual>
</link>
</model>

</world>
</sdf>
38 changes: 38 additions & 0 deletions include/gz/sim/Conversions.hh
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,7 @@
#include <sdf/ParticleEmitter.hh>
#include <sdf/Plugin.hh>
#include <sdf/Physics.hh>
#include <sdf/Projector.hh>
#include <sdf/Scene.hh>
#include <sdf/Sensor.hh>

Expand Down Expand Up @@ -714,6 +715,43 @@ namespace gz
template<>
sdf::ParticleEmitter convert(const msgs::ParticleEmitter &_in);

/// \brief Generic conversion from a projector SDF object to another
/// type.
/// \param[in] _in Projector SDF object.
/// \return Conversion result.
/// \tparam Out Output type.
template<class Out>
Out convert(const sdf::Projector &/*_in*/)
{
Out::ConversionNotImplemented;
}

/// \brief Specialized conversion from a projector SDF object to
/// a projector message object.
/// \param[in] _in Projector SDF object.
/// \return Projector message.
template<>
msgs::Projector convert(const sdf::Projector &_in);

/// \brief Generic conversion from a projector SDF object to another
/// type.
/// \param[in] _in Projector SDF object.
/// \return Conversion result.
/// \tparam Out Output type.
template<class Out>
Out convert(const msgs::Projector &/*_in*/)
{
Out::ConversionNotImplemented;
}

/// \brief Specialized conversion from a projector SDF object to
/// a projector message object.
/// \param[in] _in Projecotr SDF object.
/// \return Projector message.
template<>
sdf::Projector convert(const msgs::Projector &_in);


/// \brief Generic conversion from an SDF element to another type.
/// \param[in] _in SDF element.
/// \return Conversion result.
Expand Down
7 changes: 7 additions & 0 deletions include/gz/sim/SdfEntityCreator.hh
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@
#include <sdf/Model.hh>
#include <sdf/ParticleEmitter.hh>
#include <sdf/Physics.hh>
#include <sdf/Projector.hh>
#include <sdf/Sensor.hh>
#include <sdf/Visual.hh>
#include <sdf/World.hh>
Expand Down Expand Up @@ -155,6 +156,12 @@ namespace gz
/// \sa CreateEntities(const sdf::Link *)
public: Entity CreateEntities(const sdf::ParticleEmitter *_emitter);

/// \brief Create all entities that exist in the
/// sdf::Projector object.
/// \param[in] _projector SDF Projector object.
/// \return Projector entity.
public: Entity CreateEntities(const sdf::Projector *_projector);

/// \brief Request an entity deletion. This will insert the request
/// into a queue. The queue is processed toward the end of a simulation
/// update step.
Expand Down
Loading

0 comments on commit 42c285e

Please sign in to comment.