diff --git a/examples/worlds/shader_param.sdf b/examples/worlds/shader_param.sdf
new file mode 100644
index 0000000000..db3d48ca78
--- /dev/null
+++ b/examples/worlds/shader_param.sdf
@@ -0,0 +1,268 @@
+
+
+
+
+
+
+
+
+ ogre2
+ 0.8 0.8 0.8
+
+
+
+
+
+
+
+
+
+
+
+ 3D View
+ false
+ docked
+
+
+ ogre2
+ scene
+ 0.4 0.4 0.4
+ 0.8 0.8 0.8
+ -6 0 6 0 0.5 0
+
+
+
+
+
+ floating
+ 5
+ 5
+ false
+
+
+
+
+ false
+ 5
+ 5
+ floating
+ false
+
+
+
+
+ false
+ 5
+ 5
+ floating
+ false
+
+
+
+
+ false
+ 5
+ 5
+ floating
+ false
+
+
+
+
+
+ World control
+ false
+ false
+ 72
+ 121
+ 1
+
+ floating
+
+
+
+
+
+
+ true
+ true
+ true
+ true
+
+
+
+
+
+
+ World stats
+ false
+ false
+ 110
+ 290
+ 1
+
+ floating
+
+
+
+
+
+
+ true
+ true
+ true
+ true
+
+
+
+
+
+ docked
+
+
+
+
+
+
+ docked
+
+
+
+
+
+ RGB camera
+ floating
+ 350
+ 315
+
+ camera
+ false
+
+
+
+ Depth camera
+ floating
+ 350
+ 315
+ 500
+
+ depth_camera
+ false
+
+
+
+
+ 1.0 1.0 1.0
+ 0.8 0.8 0.8
+
+
+
+ true
+ 0 0 10 0 0 0
+ 0.8 0.8 0.8 1
+ 0.6 0.6 0.6 1
+ -0.5 0.1 -0.9
+
+
+
+ true
+
+
+
+
+ 0 0 1
+ 100 100
+
+
+
+
+
+
+ 0 0 1
+ 100 100
+
+
+
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+
+
+
+
+
+
+ 0 0.0 0.5 0 0 0
+ deformable_sphere
+ 3 0 0 0 0 0
+ https://fuel.ignitionrobotics.org/1.0/openrobotics/models/deformable_sphere
+
+
+
+ true
+ 2.5 0 0.5 0 0.0 3.14
+
+ 0.05 0.05 0.05 0 0 0
+
+
+
+ 0.1 0.1 0.1
+
+
+
+
+
+
+ 0.1 0.1 0.1
+
+
+
+
+
+ 1.047
+
+ 320
+ 240
+
+
+ 0.1
+ 100
+
+
+ 1
+ 30
+ camera
+
+
+ 10
+ depth_camera
+
+ 1.05
+
+ 320
+ 240
+
+
+ 0.1
+ 10.0
+
+
+
+
+
+
+
+
diff --git a/include/ignition/gazebo/components/Visual.hh b/include/ignition/gazebo/components/Visual.hh
index 9d90871a7b..de94818059 100644
--- a/include/ignition/gazebo/components/Visual.hh
+++ b/include/ignition/gazebo/components/Visual.hh
@@ -17,6 +17,11 @@
#ifndef IGNITION_GAZEBO_COMPONENTS_VISUAL_HH_
#define IGNITION_GAZEBO_COMPONENTS_VISUAL_HH_
+#include
+
+#include
+#include
+
#include
#include
#include
@@ -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 << ""
+ << ""
+ << _elem->ToString("")
+ << "";
+ 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(_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;
IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Visual", Visual)
+
+ /// \brief A component that contains a visual plugin's SDF element.
+ using VisualPlugin = Component;
+ IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.VisualPlugin",
+ VisualPlugin)
}
}
}
diff --git a/include/ignition/gazebo/gui/GuiEvents.hh b/include/ignition/gazebo/gui/GuiEvents.hh
index 4407d68598..afbb751879 100644
--- a/include/ignition/gazebo/gui/GuiEvents.hh
+++ b/include/ignition/gazebo/gui/GuiEvents.hh
@@ -25,8 +25,11 @@
#include
#include
#include
+
#include
#include
+#include
+
#include "ignition/gazebo/gui/Export.hh"
#include "ignition/gazebo/Entity.hh"
#include "ignition/gazebo/config.hh"
@@ -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
diff --git a/include/ignition/gazebo/rendering/Events.hh b/include/ignition/gazebo/rendering/Events.hh
index d17b3922c5..683c66f529 100644
--- a/include/ignition/gazebo/rendering/Events.hh
+++ b/include/ignition/gazebo/rendering/Events.hh
@@ -32,6 +32,18 @@ namespace ignition
/// more information about events.
namespace events
{
+ /// \brief The render event is emitted when the the scene manager is
+ /// updated with contents from the ECM. This event is emitted
+ /// before the PreRender event on the server side in the rendering
+ /// thread. It is also accessible on the GUI side.
+ ///
+ /// For example:
+ /// \code
+ /// eventManager.Emit();
+ /// \endcode
+ using SceneUpdate = ignition::common::EventT;
+
/// \brief The render event is emitted before rendering updates.
/// The event is emitted in the rendering thread so rendering
/// calls can ben make in this event callback
diff --git a/include/ignition/gazebo/rendering/RenderUtil.hh b/include/ignition/gazebo/rendering/RenderUtil.hh
index 6110b2083c..a757ec5378 100644
--- a/include/ignition/gazebo/rendering/RenderUtil.hh
+++ b/include/ignition/gazebo/rendering/RenderUtil.hh
@@ -214,6 +214,10 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \param[in] _active True if active.
public: void SetTransformActive(bool _active);
+ /// \brief Set the event manager to use
+ /// \param[in] _mgr Event manager to set to.
+ public: void SetEventManager(EventManager *_mgr);
+
/// \brief Private data pointer.
private: std::unique_ptr dataPtr;
};
diff --git a/src/SdfEntityCreator.cc b/src/SdfEntityCreator.cc
index ae98f41ec7..d54e1f377f 100644
--- a/src/SdfEntityCreator.cc
+++ b/src/SdfEntityCreator.cc
@@ -749,6 +749,17 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Visual *_visual)
components::Material(*_visual->Material()));
}
+ // store the plugin in a component
+ if (_visual->Element())
+ {
+ sdf::ElementPtr pluginElem = _visual->Element()->FindElement("plugin");
+ if (pluginElem)
+ {
+ this->dataPtr->ecm->CreateComponent(visualEntity,
+ components::VisualPlugin(pluginElem));
+ }
+ }
+
// Keep track of visuals so we can load their plugins after loading the
// entire model and having its full scoped name.
this->dataPtr->newVisuals[visualEntity] = _visual->Element();
diff --git a/src/SimulationRunner.hh b/src/SimulationRunner.hh
index a52210425e..5da194e209 100644
--- a/src/SimulationRunner.hh
+++ b/src/SimulationRunner.hh
@@ -495,9 +495,6 @@ namespace ignition
/// \brief Mutex to protect pendingSystems
private: mutable std::mutex pendingSystemsMutex;
- /// \brief Systems implementing Configure
- private: std::vector systemsConfigure;
-
/// \brief Systems implementing PreUpdate
private: std::vector systemsPreupdate;
diff --git a/src/SimulationRunner_TEST.cc b/src/SimulationRunner_TEST.cc
index cc9b33161a..17641a873c 100644
--- a/src/SimulationRunner_TEST.cc
+++ b/src/SimulationRunner_TEST.cc
@@ -1234,6 +1234,18 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) )
});
EXPECT_NE(kNullEntity, sensorId);
+ // Get visual entity
+ Entity visualId{kNullEntity};
+ runner.EntityCompMgr().Each([&](
+ const ignition::gazebo::Entity &_entity,
+ const ignition::gazebo::components::Visual *_visual)->bool
+ {
+ EXPECT_NE(nullptr, _visual);
+ visualId = _entity;
+ return true;
+ });
+ EXPECT_NE(kNullEntity, visualId);
+
// Check component registered by world plugin
std::string worldComponentName{"WorldPluginComponent"};
auto worldComponentId = ignition::common::hash64(worldComponentName);
@@ -1258,6 +1270,14 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) )
EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(sensorId,
sensorComponentId));
+ // Check component registered by visual plugin
+ std::string visualComponentName{"VisualPluginComponent"};
+ auto visualComponentId = ignition::common::hash64(visualComponentName);
+
+ EXPECT_TRUE(runner.EntityCompMgr().HasComponentType(visualComponentId));
+ EXPECT_TRUE(runner.EntityCompMgr().EntityHasComponentType(visualId,
+ visualComponentId));
+
// Clang re-registers components between tests. If we don't unregister them
// beforehand, the new plugin tries to create a storage type from a previous
// plugin, causing a crash.
@@ -1268,6 +1288,7 @@ TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) )
components::Factory::Instance()->Unregister(worldComponentId);
components::Factory::Instance()->Unregister(modelComponentId);
components::Factory::Instance()->Unregister(sensorComponentId);
+ components::Factory::Instance()->Unregister(visualComponentId);
#endif
}
diff --git a/src/gui/GuiEvents.cc b/src/gui/GuiEvents.cc
index ed195212ed..a89a5d8254 100644
--- a/src/gui/GuiEvents.cc
+++ b/src/gui/GuiEvents.cc
@@ -50,6 +50,15 @@ class ignition::gazebo::gui::events::ModelEditorAddEntity::Implementation
public: ignition::gazebo::Entity parent;
};
+class ignition::gazebo::gui::events::VisualPlugin::Implementation
+{
+ /// \brief Entity to load the visual plugin for
+ public: ignition::gazebo::Entity entity;
+
+ /// \brief Sdf element of the visual plugin
+ public: sdf::ElementPtr element;
+};
+
using namespace ignition;
using namespace gazebo;
using namespace gui;
@@ -132,3 +141,24 @@ QMap &ModelEditorAddEntity::Data()
{
return this->dataPtr->data;
}
+
+/////////////////////////////////////////////////
+VisualPlugin::VisualPlugin(ignition::gazebo::Entity _entity,
+ const sdf::ElementPtr &_elem) :
+ QEvent(kType), dataPtr(utils::MakeImpl())
+{
+ this->dataPtr->entity = _entity;
+ this->dataPtr->element = _elem;
+}
+
+/////////////////////////////////////////////////
+ignition::gazebo::Entity VisualPlugin::Entity() const
+{
+ return this->dataPtr->entity;
+}
+
+/////////////////////////////////////////////////
+sdf::ElementPtr VisualPlugin::Element() const
+{
+ return this->dataPtr->element;
+}
diff --git a/src/gui/GuiRunner.cc b/src/gui/GuiRunner.cc
index 50a2c3f075..2a70c033ac 100644
--- a/src/gui/GuiRunner.cc
+++ b/src/gui/GuiRunner.cc
@@ -15,6 +15,10 @@
*
*/
+#include
+#include
+#include
+
#include
#include
#include
@@ -28,7 +32,9 @@
#include "ignition/gazebo/components/components.hh"
#include "ignition/gazebo/Conversions.hh"
#include "ignition/gazebo/EntityComponentManager.hh"
+#include
#include "ignition/gazebo/gui/GuiSystem.hh"
+#include "ignition/gazebo/SystemLoader.hh"
#include "GuiRunner.hh"
@@ -68,6 +74,31 @@ class ignition::gazebo::GuiRunner::Implementation
/// \brief Name of WorldControl service
public: std::string controlService;
+
+ /// \brief System loader for loading ign-gazebo systems
+ public: std::unique_ptr systemLoader;
+
+ /// \brief Mutex to protect systemLoader
+ public: std::mutex systemLoadMutex;
+
+ /// \brief Events containing visual plugins to load
+ public: std::vector>
+ visualPlugins;
+
+ /// \brief Systems implementing PreUpdate
+ public: std::vector systems;
+
+ /// \brief Systems implementing PreUpdate
+ public: std::vector systemsPreupdate;
+
+ /// \brief Systems implementing Update
+ public: std::vector systemsUpdate;
+
+ /// \brief Systems implementing PostUpdate
+ public: std::vector systemsPostupdate;
+
+ /// \brief Manager of all events.
+ public: EventManager eventMgr;
};
/////////////////////////////////////////////////
@@ -92,7 +123,7 @@ GuiRunner::GuiRunner(const std::string &_worldName)
// so that an offset is not required
this->dataPtr->ecm.SetEntityCreateOffset(math::MAX_I32 / 2);
- auto win = gui::App()->findChild();
+ auto win = ignition::gui::App()->findChild();
auto winWorldNames = win->property("worldNames").toStringList();
winWorldNames.append(QString::fromStdString(_worldName));
win->setProperty("worldNames", winWorldNames);
@@ -136,7 +167,7 @@ bool GuiRunner::eventFilter(QObject *_obj, QEvent *_event)
if (_event->type() == ignition::gui::events::WorldControl::kType)
{
auto worldControlEvent =
- reinterpret_cast(_event);
+ reinterpret_cast(_event);
if (worldControlEvent)
{
msgs::WorldControlState req;
@@ -162,6 +193,20 @@ bool GuiRunner::eventFilter(QObject *_obj, QEvent *_event)
this->dataPtr->node.Request(this->dataPtr->controlService, req, cb);
}
}
+ else if (_event->type() == ignition::gazebo::gui::events::VisualPlugin::kType)
+ {
+ auto visualPluginEvent =
+ reinterpret_cast(_event);
+ if (visualPluginEvent)
+ {
+ std::lock_guard lock(this->dataPtr->systemLoadMutex);
+
+ Entity entity = visualPluginEvent->Entity();
+ sdf::ElementPtr pluginElem = visualPluginEvent->Element();
+ this->dataPtr->visualPlugins.push_back(
+ std::make_pair(entity, pluginElem));
+ }
+ }
// Standard event processing
return QObject::eventFilter(_obj, _event);
@@ -171,7 +216,7 @@ bool GuiRunner::eventFilter(QObject *_obj, QEvent *_event)
void GuiRunner::RequestState()
{
// set up service for async state response callback
- std::string id = std::to_string(gui::App()->applicationPid());
+ std::string id = std::to_string(ignition::gui::App()->applicationPid());
std::string reqSrv =
this->dataPtr->node.Options().NameSpace() + "/" + id + "/state_async";
auto reqSrvValid = transport::TopicUtils::AsValidTopic(reqSrv);
@@ -225,7 +270,7 @@ void GuiRunner::OnStateAsyncService(const msgs::SerializedStepMap &_res)
// todo(anyone) store reqSrv string in a member variable and use it here
// and in RequestState()
- std::string id = std::to_string(gui::App()->applicationPid());
+ std::string id = std::to_string(ignition::gui::App()->applicationPid());
std::string reqSrv =
this->dataPtr->node.Options().NameSpace() + "/" + id + "/state_async";
this->dataPtr->node.UnadvertiseSrv(reqSrv);
@@ -264,7 +309,8 @@ void GuiRunner::OnStateQt(const msgs::SerializedStepMap &_msg)
/////////////////////////////////////////////////
void GuiRunner::UpdatePlugins()
{
- auto plugins = gui::App()->findChildren();
+ // gui plugins
+ auto plugins = ignition::gui::App()->findChildren();
for (auto plugin : plugins)
{
plugin->Update(this->dataPtr->updateInfo, this->dataPtr->ecm);
@@ -272,4 +318,92 @@ void GuiRunner::UpdatePlugins()
this->dataPtr->ecm.ClearRemovedComponents();
this->dataPtr->ecm.ClearNewlyCreatedEntities();
this->dataPtr->ecm.ProcessRemoveEntityRequests();
+
+ // ign-gazebo systems
+ this->LoadSystems();
+ this->UpdateSystems();
+}
+
+/////////////////////////////////////////////////
+void GuiRunner::LoadSystems()
+{
+ std::lock_guard lock(this->dataPtr->systemLoadMutex);
+ // currently only support systems that are visual plugins
+ for (auto &visualPlugin : this->dataPtr->visualPlugins)
+ {
+ Entity entity = visualPlugin.first;
+ sdf::ElementPtr pluginElem = visualPlugin.second;
+ auto filename = pluginElem->Get("filename");
+ auto name = pluginElem->Get("name");
+ if (filename != "__default__" && name != "__default__")
+ {
+ std::optional system;
+ if (!this->dataPtr->systemLoader)
+ this->dataPtr->systemLoader = std::make_unique();
+ system = this->dataPtr->systemLoader->LoadPlugin(
+ filename, name, pluginElem);
+ if (system)
+ {
+ SystemPluginPtr sys = system.value();
+ this->dataPtr->systems.push_back(sys);
+ this->dataPtr->systemsPreupdate.push_back(
+ sys->QueryInterface());
+ this->dataPtr->systemsUpdate.push_back(
+ sys->QueryInterface());
+ this->dataPtr->systemsPostupdate.push_back(
+ sys->QueryInterface());
+
+ auto sysConfigure = sys->QueryInterface();
+ if (sysConfigure)
+ {
+ sysConfigure->Configure(entity, pluginElem, this->dataPtr->ecm,
+ this->dataPtr->eventMgr);
+ }
+ igndbg << "Loaded system [" << name
+ << "] for entity [" << entity << "] in GUI"
+ << std::endl;
+ }
+ }
+ }
+ this->dataPtr->visualPlugins.clear();
+}
+
+/////////////////////////////////////////////////
+void GuiRunner::UpdateSystems()
+{
+ IGN_PROFILE("GuiRunner::UpdateSystems");
+
+ {
+ IGN_PROFILE("PreUpdate");
+ for (auto& system : this->dataPtr->systemsPreupdate)
+ {
+ if (system)
+ system->PreUpdate(this->dataPtr->updateInfo, this->dataPtr->ecm);
+ }
+ }
+
+ {
+ IGN_PROFILE("Update");
+ for (auto& system : this->dataPtr->systemsUpdate)
+ {
+ if (system)
+ system->Update(this->dataPtr->updateInfo, this->dataPtr->ecm);
+ }
+ }
+
+ {
+ IGN_PROFILE("PostUpdate");
+ // \todo(anyone) Do PostUpdates in parallel
+ for (auto& system : this->dataPtr->systemsPostupdate)
+ {
+ if (system)
+ system->PostUpdate(this->dataPtr->updateInfo, this->dataPtr->ecm);
+ }
+ }
+}
+
+/////////////////////////////////////////////////
+EventManager &GuiRunner::GuiEventManager() const
+{
+ return this->dataPtr->eventMgr;
}
diff --git a/src/gui/GuiRunner.hh b/src/gui/GuiRunner.hh
index 1a06098161..bc5a730553 100644
--- a/src/gui/GuiRunner.hh
+++ b/src/gui/GuiRunner.hh
@@ -25,6 +25,7 @@
#include
#include "ignition/gazebo/config.hh"
+#include "ignition/gazebo/EventManager.hh"
#include "ignition/gazebo/gui/Export.hh"
namespace ignition
@@ -46,6 +47,9 @@ class IGNITION_GAZEBO_GUI_VISIBLE GuiRunner : public QObject
/// \brief Destructor
public: ~GuiRunner() override;
+ /// \brief Get the event manager for the gui
+ public: EventManager &GuiEventManager() const;
+
// Documentation inherited
protected: bool eventFilter(QObject *_obj, QEvent *_event) override;
@@ -74,6 +78,12 @@ class IGNITION_GAZEBO_GUI_VISIBLE GuiRunner : public QObject
/// \todo(anyone) Move to GuiRunner::Implementation when porting to v5
private: Q_INVOKABLE void UpdatePlugins();
+ /// \brief Load systems
+ private: void LoadSystems();
+
+ /// \brief Update systems
+ private: void UpdateSystems();
+
/// \brief Pointer to private data.
IGN_UTILS_UNIQUE_IMPL_PTR(dataPtr)
};
diff --git a/src/gui/plugins/scene_manager/GzSceneManager.cc b/src/gui/plugins/scene_manager/GzSceneManager.cc
index cccb6caaa4..48c0735f10 100644
--- a/src/gui/plugins/scene_manager/GzSceneManager.cc
+++ b/src/gui/plugins/scene_manager/GzSceneManager.cc
@@ -14,10 +14,15 @@
* limitations under the License.
*
*/
+
+#include