Skip to content

Commit

Permalink
Load and run visual plugin (system) on GUI side (#1275)
Browse files Browse the repository at this point in the history
* load and run visual plugins on gui end

Signed-off-by: Ian Chen <[email protected]>

* scene update event emitted on both server and gui side

Signed-off-by: Ian Chen <[email protected]>

* shader param update working

Signed-off-by: Ian Chen <[email protected]>

* sim time, constants, full example working

Signed-off-by: Ian Chen <[email protected]>

* add integration test

Signed-off-by: Ian Chen <[email protected]>

* code cleanup

Signed-off-by: Ian Chen <[email protected]>

* more code cleanup

Signed-off-by: Ian Chen <[email protected]>

* style fixes and add some comments

Signed-off-by: Ian Chen <[email protected]>

* review changes

Signed-off-by: Ian Chen <[email protected]>

* require display for shader param test

Signed-off-by: Ian Chen <[email protected]>

* style and comment

Signed-off-by: Ian Chen <[email protected]>
  • Loading branch information
iche033 authored Feb 4, 2022
1 parent 912e2ce commit 717a7e9
Show file tree
Hide file tree
Showing 24 changed files with 1,371 additions and 10 deletions.
268 changes: 268 additions & 0 deletions examples/worlds/shader_param.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,268 @@
<?xml version="1.0" ?>
<!--
This world contains a sphere model whose visual appearance is altered by the
ShaderParam visual plugin over time.
-->
<sdf version="1.6">
<world name="deformable_sphere">

<plugin
filename="ignition-gazebo-physics-system"
name="ignition::gazebo::systems::Physics">
</plugin>
<plugin
filename="ignition-gazebo-sensors-system"
name="ignition::gazebo::systems::Sensors">
<render_engine>ogre2</render_engine>
<background_color>0.8 0.8 0.8</background_color>
</plugin>
<plugin
filename="ignition-gazebo-scene-broadcaster-system"
name="ignition::gazebo::systems::SceneBroadcaster">
</plugin>
<plugin
filename="ignition-gazebo-user-commands-system"
name="ignition::gazebo::systems::UserCommands">
</plugin>

<gui fullscreen="0">

<!-- 3D scene -->
<plugin filename="MinimalScene" 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>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">
<ignition-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>
</ignition-gui>
</plugin>
<plugin filename="GzSceneManager" name="Scene Manager">
<ignition-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>
</ignition-gui>
</plugin>
<plugin filename="InteractiveViewControl" name="Interactive view control">
<ignition-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>
</ignition-gui>
</plugin>
<plugin filename="CameraTracking" name="Camera Tracking">
<ignition-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>
</ignition-gui>
</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>
<use_event>true</use_event>

</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>

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

<!-- Entity tree -->
<plugin filename="EntityTree" name="Entity tree">
<ignition-gui>
<property type="string" key="state">docked</property>
</ignition-gui>
</plugin>

<plugin filename="ImageDisplay" name="Image Display">
<ignition-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>
</ignition-gui>
<topic>camera</topic>
<topic_picker>false</topic_picker>
</plugin>
<plugin filename="ImageDisplay" name="Image Display 2">
<ignition-gui>
<title>Depth 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="x">500</property>
</ignition-gui>
<topic>depth_camera</topic>
<topic_picker>false</topic_picker>
</plugin>
</gui>

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

<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.6 0.6 0.6 1</specular>
<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.0 0.5 0 0 0</pose>
<name>deformable_sphere</name>
<pose>3 0 0 0 0 0</pose>
<uri>https://fuel.ignitionrobotics.org/1.0/openrobotics/models/deformable_sphere</uri>
</include>

<model name="camera">
<static>true</static>
<pose>2.5 0 0.5 0 0.0 3.14</pose>
<link name="link">
<pose>0.05 0.05 0.05 0 0 0</pose>
<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="camera" type="camera">
<camera>
<horizontal_fov>1.047</horizontal_fov>
<image>
<width>320</width>
<height>240</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<topic>camera</topic>
</sensor>
<sensor name="depth_camera" type="depth_camera">
<update_rate>10</update_rate>
<topic>depth_camera</topic>
<camera>
<horizontal_fov>1.05</horizontal_fov>
<image>
<width>320</width>
<height>240</height>
</image>
<clip>
<near>0.1</near>
<far>10.0</far>
</clip>
</camera>
</sensor>
</link>
</model>

</world>
</sdf>
54 changes: 54 additions & 0 deletions include/ignition/gazebo/components/Visual.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,11 @@
#ifndef IGNITION_GAZEBO_COMPONENTS_VISUAL_HH_
#define IGNITION_GAZEBO_COMPONENTS_VISUAL_HH_

#include <string>

#include <sdf/parser.hh>
#include <sdf/Element.hh>

#include <ignition/gazebo/components/Factory.hh>
#include <ignition/gazebo/components/Component.hh>
#include <ignition/gazebo/config.hh>
Expand All @@ -27,11 +32,60 @@ namespace gazebo
{
// Inline bracket to help doxygen filtering.
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace serializers
{
class SdfElementSerializer
{
/// \brief Serialization for `sdf::Model`.
/// \param[in] _out Output stream.
/// \param[in] _elem Visual plugin elem to stream
/// \return The stream.
public: static std::ostream &Serialize(std::ostream &_out,
const sdf::ElementPtr &_elem)
{
_out << "<?xml version=\"1.0\" ?>"
<< "<sdf version='" << SDF_PROTOCOL_VERSION << "'>"
<< _elem->ToString("")
<< "</sdf>";
return _out;
}

/// \brief Deserialization for `sdf::Element`.
/// \param[in] _in Input stream.
/// \param[out] _elem Visual plugin elem to populate
/// \return The stream.
public: static std::istream &Deserialize(std::istream &_in,
sdf::ElementPtr &_elem)
{
std::string sdfStr(std::istreambuf_iterator<char>(_in), {});

sdf::SDFPtr sdfParsed(new sdf::SDF());
sdf::init(sdfParsed);
bool result = sdf::readString(sdfStr, sdfParsed);
if (!result)
{
ignerr << "Unable to deserialize sdf::ElementPtr" << std::endl;
return _in;
}

_elem = sdfParsed->Root()->GetFirstElement();
return _in;
}
};
}

namespace components
{
/// \brief A component that identifies an entity as being a visual.
using Visual = Component<NoData, class VisualTag>;
IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Visual", Visual)

/// \brief A component that contains a visual plugin's SDF element.
using VisualPlugin = Component<sdf::ElementPtr,
class VisualPluginTag,
serializers::SdfElementSerializer>;
IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.VisualPlugin",
VisualPlugin)
}
}
}
Expand Down
24 changes: 24 additions & 0 deletions include/ignition/gazebo/gui/GuiEvents.hh
Original file line number Diff line number Diff line change
Expand Up @@ -25,8 +25,11 @@
#include <string>
#include <utility>
#include <vector>

#include <ignition/math/Vector3.hh>
#include <ignition/utils/ImplPtr.hh>
#include <sdf/Element.hh>

#include "ignition/gazebo/gui/Export.hh"
#include "ignition/gazebo/Entity.hh"
#include "ignition/gazebo/config.hh"
Expand Down Expand Up @@ -211,6 +214,27 @@ namespace events
IGN_UTILS_IMPL_PTR(dataPtr)
};

/// \brief Event that notifies a visual plugin is to be loaded
class IGNITION_GAZEBO_GUI_VISIBLE VisualPlugin: public QEvent
{
/// \brief Constructor
/// \param[in] _entity Visual entity id
/// \param[in] _elem Visual plugin SDF element
public: explicit VisualPlugin(ignition::gazebo::Entity _entity,
const sdf::ElementPtr &_elem);

/// \brief Get the entity to load the visual plugin for
public: ignition::gazebo::Entity Entity() const;

/// \brief Get the sdf element of the visual plugin
public: sdf::ElementPtr Element() const;

static const QEvent::Type kType = QEvent::Type(QEvent::User + 8);

/// \internal
/// \brief Private data pointer
IGN_UTILS_IMPL_PTR(dataPtr)
};
} // namespace events
}
} // namespace gui
Expand Down
Loading

0 comments on commit 717a7e9

Please sign in to comment.