Skip to content

Commit

Permalink
Add a flexible mechanism to combine user and default plugins (#2497)
Browse files Browse the repository at this point in the history

Signed-off-by: Addisu Z. Taddese <[email protected]>
Signed-off-by: Ian Chen <[email protected]>
Co-authored-by: Ian Chen <[email protected]>
  • Loading branch information
azeey and iche033 authored Aug 29, 2024
1 parent 8b1dbda commit a893657
Show file tree
Hide file tree
Showing 16 changed files with 476 additions and 188 deletions.
115 changes: 4 additions & 111 deletions examples/worlds/camera_sensor.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -8,127 +8,34 @@
<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>

<gz:policies>
<include_gui_default_plugins>true</include_gui_default_plugins>
</gz:policies>
<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="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>
<camera_pose>-3 0 3 0 0.5 0</camera_pose>
</plugin>

<plugin filename="ImageDisplay" name="Image Display">
Expand All @@ -137,20 +44,6 @@
</gz-gui>
<topic>camera</topic>
</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">
Expand Down
17 changes: 1 addition & 16 deletions examples/worlds/contact_sensor.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -9,22 +9,7 @@ Run the following to print out contacts,
-->

<world name="contact_sensor">
<plugin
filename="gz-sim-physics-system"
name="gz::sim::systems::Physics">
</plugin>
<plugin
filename="gz-sim-contact-system"
name="gz::sim::systems::Contact">
</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>
<plugin filename="gz-sim-contact-system" name="gz::sim::systems::Contact"/>

<scene>
<grid>false</grid>
Expand Down
4 changes: 4 additions & 0 deletions examples/worlds/mimic_fast_slow_pendulums_world.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,10 @@
<real_time_factor>1</real_time_factor>
</physics>

<plugin filename="gz-sim-physics-system" name="gz::sim::systems::Physics">
<engine><filename>gz-physics-bullet-featherstone-plugin</filename></engine>
</plugin>

<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
Expand Down
12 changes: 0 additions & 12 deletions examples/worlds/quadcopter.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -17,18 +17,6 @@
<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-scene-broadcaster-system"
name="gz::sim::systems::SceneBroadcaster">
</plugin>
<plugin
filename="gz-sim-user-commands-system"
name="gz::sim::systems::UserCommands">
</plugin>
<plugin
filename="gz-sim-sensors-system"
name="gz::sim::systems::Sensors">
Expand Down
33 changes: 33 additions & 0 deletions include/gz/sim/Constants.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
/*
* Copyright (C) 2024 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#ifndef GZ_SIM_CONSTANTS_HH_
#define GZ_SIM_CONSTANTS_HH_

#include "gz/sim/config.hh"
#include <string_view>

namespace gz::sim
{
// Inline bracket to help doxygen filtering.
inline namespace GZ_SIM_VERSION_NAMESPACE
{
constexpr std::string_view kPoliciesTag{"gz:policies"};
}
} // namespace gz::sim

#endif
4 changes: 2 additions & 2 deletions src/ServerConfig.cc
Original file line number Diff line number Diff line change
Expand Up @@ -938,7 +938,7 @@ sim::loadPluginInfo(bool _isPlayback)
gzwarn << kServerConfigPathEnv
<< " set but no plugins found\n";
}
gzdbg << "Loaded (" << ret.size() << ") plugins from file " <<
gzdbg << "Loading (" << ret.size() << ") plugins from file " <<
"[" << envConfig << "]\n";

return ret;
Expand Down Expand Up @@ -1018,7 +1018,7 @@ sim::loadPluginInfo(bool _isPlayback)
<< "], but no plugins found\n";
}

gzdbg << "Loaded (" << ret.size() << ") plugins from file " <<
gzdbg << "Loading (" << ret.size() << ") plugins from file " <<
"[" << defaultConfig << "]\n";

return ret;
Expand Down
6 changes: 2 additions & 4 deletions src/Server_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -442,8 +442,7 @@ TEST_P(ServerFixture, GZ_UTILS_TEST_DISABLED_ON_WIN32(ServerConfigLogRecord))

EXPECT_EQ(0u, *server.IterationCount());
EXPECT_EQ(3u, *server.EntityCount());
// Only the log record system is needed and therefore loaded.
EXPECT_EQ(1u, *server.SystemCount());
EXPECT_EQ(4u, *server.SystemCount());

EXPECT_TRUE(serverConfig.LogRecordTopics().empty());
serverConfig.AddLogRecordTopic("test_topic1");
Expand Down Expand Up @@ -483,8 +482,7 @@ TEST_P(ServerFixture,
EXPECT_EQ(0u, *server.IterationCount());
EXPECT_EQ(3u, *server.EntityCount());

// Only the log record system is needed and therefore loaded.
EXPECT_EQ(1u, *server.SystemCount());
EXPECT_EQ(4u, *server.SystemCount());
}

EXPECT_FALSE(common::exists(logFile));
Expand Down
74 changes: 64 additions & 10 deletions src/SimulationRunner.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include "SimulationRunner.hh"

#include <algorithm>
#include <unordered_set>
#ifdef HAVE_PYBIND11
#include <pybind11/pybind11.h>
#endif
Expand All @@ -36,6 +37,7 @@
#include <vector>

#include "gz/common/Profiler.hh"
#include "gz/sim/Constants.hh"
#include "gz/sim/components/Model.hh"
#include "gz/sim/components/Name.hh"
#include "gz/sim/components/Sensor.hh"
Expand All @@ -50,6 +52,7 @@
#include "gz/sim/components/RenderEngineServerHeadless.hh"
#include "gz/sim/components/RenderEngineServerPlugin.hh"
#include "gz/sim/Events.hh"
#include "gz/sim/ServerConfig.hh"
#include "gz/sim/SdfEntityCreator.hh"
#include "gz/sim/Util.hh"
#include "gz/transport/TopicUtils.hh"
Expand Down Expand Up @@ -263,6 +266,18 @@ SimulationRunner::SimulationRunner(const sdf::World &_world,
if (_world.Gui())
{
this->guiMsg = convert<msgs::GUI>(*_world.Gui());

auto worldElem = this->sdfWorld.Element();
if (worldElem)
{
auto policies = worldElem->FindElement("gz:policies");
if (policies)
{
auto headerData = this->guiMsg.mutable_header()->add_data();
headerData->set_key("gz:policies");
headerData->add_value(policies->ToString(""));
}
}
}

std::string infoService{"gui/info"};
Expand Down Expand Up @@ -1586,21 +1601,60 @@ void SimulationRunner::CreateEntities(const sdf::World &_world)
// Load any additional plugins from the Server Configuration
this->LoadServerPlugins(this->serverConfig.Plugins());

auto loadedWorldPlugins = this->systemMgr->TotalByEntity(worldEntity);
// If we have reached this point and no world systems have been loaded, then
// load a default set of systems.
if (this->systemMgr->TotalByEntity(worldEntity).empty())

auto worldElem = this->sdfWorld.Element();
bool includeServerConfigPlugins = true;
if (worldElem)
{
gzmsg << "No systems loaded from SDF, loading defaults" << std::endl;
bool isPlayback = !this->serverConfig.LogPlaybackPath().empty();
auto plugins = gz::sim::loadPluginInfo(isPlayback);
this->LoadServerPlugins(plugins);
auto policies = worldElem->FindElement(std::string(kPoliciesTag));
if (policies)
{
includeServerConfigPlugins =
policies
->Get<bool>("include_server_config_plugins", includeServerConfigPlugins)
.first;
}
}

if (includeServerConfigPlugins || loadedWorldPlugins.empty())
{
bool isPlayback = !this->serverConfig.LogPlaybackPath().empty();
auto defaultPlugins = gz::sim::loadPluginInfo(isPlayback);
if (loadedWorldPlugins.empty())
{
gzmsg << "No systems loaded from SDF, loading defaults" << std::endl;
}
else
{
std::unordered_set<std::string> loadedWorldPluginFileNames;
for (const auto &pl : loadedWorldPlugins)
{
loadedWorldPluginFileNames.insert(pl.fname);
}
auto isPluginLoaded =
[&loadedWorldPluginFileNames](const ServerConfig::PluginInfo &_pl)
{
return loadedWorldPluginFileNames.count(_pl.Plugin().Filename()) != 0;
};

// Remove plugin if it's already loaded so as to not duplicate world
// plugins.
defaultPlugins.remove_if(isPluginLoaded);

gzdbg << "Additional plugins to load:\n";
for (const auto &plugin : defaultPlugins)
{
gzdbg << plugin.Plugin().Name() << " " << plugin.Plugin().Filename()
<< "\n";
}
}

this->LoadServerPlugins(defaultPlugins);
};

// Store the initial state of the ECM;
this->initialEntityCompMgr.CopyFrom(this->entityCompMgr);

// Publish empty GUI messages for worlds that have no GUI in the beginning.
// In the future, support modifying GUI from the server at runtime.
if (_world.Gui())
this->guiMsg = convert<msgs::GUI>(*_world.Gui());
}
Loading

0 comments on commit a893657

Please sign in to comment.