From 02fca21d0011f3df40dd67bd20b1b04595a62669 Mon Sep 17 00:00:00 2001
From: "Addisu Z. Taddese"
Date: Wed, 24 Jul 2024 17:50:38 -0500
Subject: [PATCH 01/15] Add a flexible mechanism to combine user and default
plugins
Signed-off-by: Addisu Z. Taddese
---
examples/worlds/camera_sensor.sdf | 117 +--------
examples/worlds/contact_sensor.sdf | 17 +-
examples/worlds/empty.sdf | 11 +-
.../mimic_fast_slow_pendulums_world.sdf | 4 +
examples/worlds/quadcopter.sdf | 12 -
examples/worlds/shapes.sdf | 10 +
src/LevelManager.cc | 6 +-
src/SimulationRunner.cc | 107 +++++++-
src/gui/Gui.cc | 244 ++++++++++++++----
9 files changed, 318 insertions(+), 210 deletions(-)
diff --git a/examples/worlds/camera_sensor.sdf b/examples/worlds/camera_sensor.sdf
index 3d967d701e..50ecfd158b 100644
--- a/examples/worlds/camera_sensor.sdf
+++ b/examples/worlds/camera_sensor.sdf
@@ -8,23 +8,11 @@
0.001
1.0
-
-
ogre2
-
-
-
-
1.0 1.0 1.0
@@ -32,125 +20,32 @@
true
+
+ false
+
-
+ prepend_replace
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
- 1
-
- floating
-
-
-
-
-
-
- true
- true
- true
- true
-
-
-
-
-
-
- World stats
- false
- false
- 110
- 290
- 1
-
- floating
-
-
-
-
-
-
- true
- true
- true
- true
+ -3 0 3 0 0.5 0
+ append
docked
camera
-
-
-
-
- docked
-
-
-
-
-
-
- docked
-
-
diff --git a/examples/worlds/contact_sensor.sdf b/examples/worlds/contact_sensor.sdf
index c37f7f259b..0714c34bf7 100644
--- a/examples/worlds/contact_sensor.sdf
+++ b/examples/worlds/contact_sensor.sdf
@@ -9,22 +9,7 @@ Run the following to print out contacts,
-->
-
-
-
-
-
-
-
-
+
false
diff --git a/examples/worlds/empty.sdf b/examples/worlds/empty.sdf
index 3f0ad8dfda..aa08b76fcc 100644
--- a/examples/worlds/empty.sdf
+++ b/examples/worlds/empty.sdf
@@ -65,19 +65,14 @@ gz service -s /world/empty/create \
0.001
1.0
+
+ bullet
-
-
-
-
diff --git a/examples/worlds/mimic_fast_slow_pendulums_world.sdf b/examples/worlds/mimic_fast_slow_pendulums_world.sdf
index b42c8bc73a..7386bd3dac 100644
--- a/examples/worlds/mimic_fast_slow_pendulums_world.sdf
+++ b/examples/worlds/mimic_fast_slow_pendulums_world.sdf
@@ -16,6 +16,10 @@
1
+
+ gz-physics-bullet-featherstone-plugin
+
+
true
0 0 10 0 0 0
diff --git a/examples/worlds/quadcopter.sdf b/examples/worlds/quadcopter.sdf
index 4b00c86c15..1ec3eaa18e 100644
--- a/examples/worlds/quadcopter.sdf
+++ b/examples/worlds/quadcopter.sdf
@@ -17,18 +17,6 @@
0.001
1.0
-
-
-
-
-
-
diff --git a/examples/worlds/shapes.sdf b/examples/worlds/shapes.sdf
index 5d020a8c32..ecdc64bce0 100644
--- a/examples/worlds/shapes.sdf
+++ b/examples/worlds/shapes.sdf
@@ -9,6 +9,16 @@
--timeout 300 --req 'name: "box", position: {z: 5.0}'
]]>
+
+ true
+
+
+ prepend_replace
+ gz-physics-bullet-featherstone-plugin
+
+
+ append
+
1.0 1.0 1.0
0.8 0.8 0.8
diff --git a/src/LevelManager.cc b/src/LevelManager.cc
index 8f0ace19ae..dc5e4c4ce2 100644
--- a/src/LevelManager.cc
+++ b/src/LevelManager.cc
@@ -249,9 +249,9 @@ void LevelManager::ReadLevelPerformerInfo()
this->ConfigureDefaultLevel();
- // Load world plugins.
- this->runner->EventMgr().Emit(this->worldEntity,
- this->runner->sdfWorld->Plugins());
+ /* // Load world plugins. */
+ /* this->runner->EventMgr().Emit(this->worldEntity, */
+ /* this->runner->sdfWorld->Plugins()); */
// Store the world's SDF DOM to be used when saving the world to file
this->runner->entityCompMgr.CreateComponent(
diff --git a/src/SimulationRunner.cc b/src/SimulationRunner.cc
index 87f72d1ce2..825d8e7f97 100644
--- a/src/SimulationRunner.cc
+++ b/src/SimulationRunner.cc
@@ -18,6 +18,7 @@
#include "SimulationRunner.hh"
#include
+#include
#ifdef HAVE_PYBIND11
#include
#endif
@@ -36,6 +37,7 @@
#include
#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"
@@ -252,23 +254,94 @@ SimulationRunner::SimulationRunner(const sdf::World *_world,
// Load the active levels
this->levelMgr->UpdateLevelsState();
- // Store the initial state of the ECM;
- this->initialEntityCompMgr.CopyFrom(this->entityCompMgr);
+ auto worldElem = this->sdfWorld->Element();
+ bool noDefaultServerPlugins = false;
+ bool noDefaultGuiPlugins = false;
+ if (worldElem)
+ {
+ auto policies = worldElem->FindElement("gz:policies");
+ if (policies)
+ {
+ noDefaultServerPlugins =
+ policies
+ ->Get("no_default_server_plugins", noDefaultServerPlugins)
+ .first;
+ noDefaultGuiPlugins =
+ policies->Get("no_default_gui_plugins", noDefaultGuiPlugins)
+ .first;
+ }
+ }
- // Load any additional plugins from the Server Configuration
- this->LoadServerPlugins(this->serverConfig.Plugins());
+ auto getUserPlugins = [&]()
+ {
+ std::list userPlugins;
+ for (const auto &plugin : this->sdfWorld->Plugins())
+ {
+ userPlugins.emplace_back("*", "world", plugin);
+ }
+ return userPlugins;
+ };
- // 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(this->entityCompMgr)).empty())
+ auto combineUserAndDefaultPlugins =
+ [](const auto &_userPlugins, const auto &_defaultPlugins, bool _policy)
{
- gzmsg << "No systems loaded from SDF, loading defaults" << std::endl;
- bool isPlayback = !this->serverConfig.LogPlaybackPath().empty();
- auto plugins = sim::loadPluginInfo(isPlayback);
- this->LoadServerPlugins(plugins);
+ // TODO(azeey) Handle serverConfigPlugins
+ /* auto serverConfigPlugins = this->serverConfig.Plugins(); */
+ if (!_policy)
+ {
+ auto combinedPlugins = _defaultPlugins;
+ for (const auto &userPlugin : _userPlugins)
+ {
+ auto pluginElem = userPlugin.Plugin().Element();
+ assert(pluginElem);
+ auto configAction = pluginElem
+ ->template Get("gz:config_action",
+ "append_replace")
+ .first;
+ gzmsg << "Plugin: " << userPlugin.Plugin().Filename() << " act: " << configAction << "\n";
+ if (configAction == config_action::kPrependReplace ||
+ configAction == config_action::kAppendReplace)
+ {
+ // Remove all matching plugins
+ combinedPlugins.remove_if(
+ [&](const auto &_pl) {
+ return _pl.Plugin().Filename() ==
+ userPlugin.Plugin().Filename();
+ });
+ }
+ if (configAction == config_action::kPrependReplace ||
+ configAction == config_action::kPrepend)
+ {
+ // Remove all matching plugins
+ combinedPlugins.push_front(userPlugin);
+ }
+ else if (configAction == config_action::kAppendReplace ||
+ configAction == config_action::kAppend)
+ {
+ combinedPlugins.push_back(userPlugin);
+ }
+ }
+ return combinedPlugins;
+ }
+ return _userPlugins;
+ };
+ bool isPlayback = !this->serverConfig.LogPlaybackPath().empty();
+ // TODO(azeey) Let's assume these are just default plugins. loadPluginInfo
+ // can also load from a custom config file, so we need to handle that
+ // differently
+ auto pluginsToLoad = combineUserAndDefaultPlugins(
+ getUserPlugins(), sim::loadPluginInfo(isPlayback),
+ noDefaultServerPlugins);
+ gzdbg << "Loading plugins:\n";
+ for (const auto &plugin: pluginsToLoad) {
+ gzdbg << plugin.Plugin().Name() << "\n";
+ /* gzdbg << plugin.Plugin().Element()->ToString("\t"); */
}
+ this->LoadServerPlugins(pluginsToLoad);
+ // Store the initial state of the ECM;
+ this->initialEntityCompMgr.CopyFrom(this->entityCompMgr);
+
this->LoadLoggingPlugins(this->serverConfig);
// TODO(louise) Combine both messages into one.
@@ -287,6 +360,16 @@ SimulationRunner::SimulationRunner(const sdf::World *_world,
if (_world->Gui())
{
this->guiMsg = convert(*_world->Gui());
+ 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"};
diff --git a/src/gui/Gui.cc b/src/gui/Gui.cc
index 72c6335e4d..a653954139 100644
--- a/src/gui/Gui.cc
+++ b/src/gui/Gui.cc
@@ -18,6 +18,7 @@
#include
#include
#include
+#include
#include
@@ -29,7 +30,9 @@
#include
#include
#include
+#include
+#include "gz/sim/Constants.hh"
#include "gz/sim/InstallationDirectories.hh"
#include "gz/sim/Util.hh"
#include "gz/sim/config.hh"
@@ -390,11 +393,11 @@ std::unique_ptr createGui(
result = false;
gz::msgs::GUI res;
service = transport::TopicUtils::AsValidTopic("/world/" + worldName +
- "/gui/info");
+ "/gui/info");
if (service.empty())
{
gzerr << "Failed to generate valid service for world [" << worldName
- << "]" << std::endl;
+ << "]" << std::endl;
}
else
{
@@ -406,7 +409,7 @@ std::unique_ptr createGui(
if (!executed)
{
gzerr << "Service call timed out for [" << service << "]"
- << std::endl;
+ << std::endl;
}
else if (!result)
{
@@ -419,62 +422,207 @@ std::unique_ptr createGui(
runner->setParent(gz::gui::App());
++runnerCount;
+ bool noDefaultGuiPlugins = false;
+ std::cout << res.DebugString() << std::endl;
+ for (const auto &data : res.header().data())
+ {
+ if (data.key() == "gz:policies")
+ {
+ tinyxml2::XMLDocument doc;
+ if (data.value_size() > 0)
+ {
+ if (doc.Parse(data.value(0).c_str()) == tinyxml2::XML_SUCCESS)
+ {
+ tinyxml2::XMLHandle handle(doc);
+ auto elem = handle.FirstChildElement("gz:policies")
+ .FirstChildElement("no_default_gui_plugins")
+ .ToElement();
+ if (elem)
+ {
+ elem->QueryBoolText(&noDefaultGuiPlugins);
+ }
+ }
+ }
+ }
+ }
+
+ gzmsg << "no_default_gui_plugins: " << noDefaultGuiPlugins << "\n";
// Load plugins after creating GuiRunner, so they can access worldName
if (_loadPluginsFromSdf)
{
- for (int p = 0; p < res.plugin_size(); ++p)
+ auto getUserPlugins = [&]()
{
- const auto &plugin = res.plugin(p);
- auto fileName = plugin.filename();
-
- // Redirect GzScene3D to MinimalScene for backwards compatibility,
- // with warnings
- if (fileName == "GzScene3D")
+ auto userPluginsDoc = std::make_unique();
+ std::string pluginsXml = "";
+ for (int p = 0; p < res.plugin_size(); ++p)
{
- std::vector extras{"GzSceneManager",
- "InteractiveViewControl",
- "CameraTracking",
- "MarkerManager",
- "SelectEntities",
- "EntityContextMenuPlugin",
- "Spawn",
- "VisualizationCapabilities"};
-
- std::string msg{
- "The [GzScene3D] GUI plugin has been removed since Garden.\n"
- "SDF code to replace GzScene3D is available at "
- "https://github.com/gazebosim/gz-sim/blob/gz-sim7/Migration.md\n"
- "Loading the following plugins instead:\n"};
-
- for (auto extra : extras)
+ const auto &plugin = res.plugin(p);
+ auto fileName = plugin.filename();
+ // Redirect GzScene3D to MinimalScene for backwards compatibility,
+ // with warnings
+ if (fileName == "GzScene3D")
{
- msg += "* " + extra + "\n";
-
- auto newPlugin = res.add_plugin();
- newPlugin->set_filename(extra);
- newPlugin->set_innerxml(std::string(
- ""
- " floating"
- " 5"
- " 5"
- " false"
- " false"
- ""));
+ std::vector extras{
+ "GzSceneManager", "InteractiveViewControl",
+ "CameraTracking", "MarkerManager",
+ "SelectEntities", "EntityContextMenuPlugin",
+ "Spawn", "VisualizationCapabilities"};
+
+ std::string msg{
+ "The [GzScene3D] GUI plugin has been removed since Garden.\n"
+ "SDF code to replace GzScene3D is available at "
+ "https://github.com/gazebosim/gz-sim/blob/gz-sim7/"
+ "Migration.md\n"
+ "Loading the following plugins instead:\n"};
+
+ for (auto extra : extras)
+ {
+ msg += "* " + extra + "\n";
+
+ auto newPlugin = res.add_plugin();
+ newPlugin->set_filename(extra);
+ newPlugin->set_innerxml(std::string(
+ ""
+ " floating"
+ " 5"
+ " 5"
+ " false"
+ " false"
+ ""));
+ }
+
+ gzwarn << msg;
+
+ fileName = "MinimalScene";
}
-
- gzwarn << msg;
-
- fileName = "MinimalScene";
+ pluginsXml += "" +
+ plugin.innerxml() + "\n";
}
+ userPluginsDoc->Parse(pluginsXml.c_str());
+ return userPluginsDoc;
+ };
- std::string pluginStr = "" +
- plugin.innerxml() + "";
+ auto getDefaultPlugins = [&]()
+ {
+ const auto resolvedDefaultConfigPath =
+ app->ResolveConfigFile(defaultConfig);
+ auto pluginsDoc = std::make_unique();
+ if (pluginsDoc->LoadFile(resolvedDefaultConfigPath.c_str()) ==
+ tinyxml2::XML_SUCCESS)
+ {
+ // Remove everything that's not a plugin
+ for (auto elem = pluginsDoc->FirstChildElement(); elem != nullptr;)
+ {
+ if (std::strcmp("plugin", elem->Value()) != 0)
+ {
+ auto tmp = elem;
+ elem = elem->NextSiblingElement();
+ pluginsDoc->DeleteChild(tmp);
+ }
+ else
+ {
+ elem = elem->NextSiblingElement();
+ }
+ }
+ }
- tinyxml2::XMLDocument pluginDoc;
- pluginDoc.Parse(pluginStr.c_str());
+ return pluginsDoc;
+ };
- app->LoadPlugin(fileName,
- pluginDoc.FirstChildElement("plugin"));
+ auto combineUserAndDefaultPlugins =
+ [](std::unique_ptr _userPlugins,
+ const std::unique_ptr& _defaultPlugins,
+ bool _policy)
+ {
+ if (!_policy)
+ {
+ auto combinedPlugins = std::make_unique();
+ _defaultPlugins->DeepCopy(combinedPlugins.get());
+ for (auto pluginElem = _userPlugins->FirstChildElement("plugin");
+ pluginElem != nullptr;
+ pluginElem = pluginElem->NextSiblingElement("plugin"))
+ {
+ const char *pluginFilename = pluginElem->Attribute("filename");
+ std::string configAction = "";
+
+ auto configActionElement = pluginElem->FirstChildElement(config_action::kPluginAttribute.data());
+ if (configActionElement)
+ {
+ configAction = configActionElement->GetText();
+ }
+
+ if (configAction == "")
+ {
+ configAction = config_action::kAppendReplace;
+ }
+
+ gzmsg << "Plugin: " << pluginFilename << " act: " << configAction << "\n";
+
+ if (configAction == config_action::kPrependReplace ||
+ configAction == config_action::kAppendReplace)
+ {
+ // Remove all matching plugins
+ for (auto elem = combinedPlugins->FirstChildElement("plugin");
+ elem != nullptr;)
+ {
+ if (elem->Attribute("filename", pluginFilename))
+ {
+ gzmsg << "\t Removing " << pluginFilename << "\n";
+ auto tmp = elem;
+ elem = elem->NextSiblingElement("plugin");
+ combinedPlugins->DeleteNode(tmp);
+ }
+ else
+ {
+ elem = elem->NextSiblingElement("plugin");
+ }
+ }
+ }
+ auto clonedPlugin = pluginElem->DeepClone(combinedPlugins.get());
+ if (configAction == config_action::kPrependReplace ||
+ configAction == config_action::kPrepend)
+ {
+ combinedPlugins->InsertFirstChild(clonedPlugin);
+ }
+ else if (configAction == config_action::kAppendReplace ||
+ configAction == config_action::kAppend)
+ {
+ combinedPlugins->InsertEndChild(clonedPlugin);
+ }
+ else {
+ gzerr << "Unknown config action: " << configAction << std::endl;
+ }
+ }
+ return combinedPlugins;
+ }
+ return _userPlugins;
+ };
+ auto printPlugins = [](const tinyxml2::XMLDocument &_plugins)
+ {
+ tinyxml2::XMLPrinter printer;
+ _plugins.Print( &printer );
+ gzdbg << printer.CStr() << std::endl;
+ };
+
+ auto userPlugins = getUserPlugins();
+ gzwarn << "User plugins:\n";
+ printPlugins(*userPlugins);
+ auto defaultPlugins = getDefaultPlugins();
+ gzwarn << "Default plugins:\n";
+ printPlugins(*defaultPlugins);
+ auto pluginsToLoad = combineUserAndDefaultPlugins(
+ std::move(userPlugins), defaultPlugins, noDefaultGuiPlugins);
+ gzwarn << "Plugins to load:\n";
+ printPlugins(*pluginsToLoad);
+
+ gzwarn << "Loading plugins:\n";
+ for (auto pluginElem = pluginsToLoad->FirstChildElement("plugin");
+ pluginElem != nullptr;
+ pluginElem = pluginElem->NextSiblingElement("plugin"))
+ {
+ app->LoadPlugin(pluginElem->Attribute("filename"), pluginElem);
+ gzdbg << pluginElem->Attribute("filename") << "\n";
}
}
}
From bc7e3546458a97085b3c255f6d1da41dcd5c1827 Mon Sep 17 00:00:00 2001
From: "Addisu Z. Taddese"
Date: Fri, 26 Jul 2024 09:41:26 -0500
Subject: [PATCH 02/15] Add missing file
Signed-off-by: Addisu Z. Taddese
---
include/gz/sim/Constants.hh | 39 +++++++++++++++++++++++++++++++++++++
1 file changed, 39 insertions(+)
create mode 100644 include/gz/sim/Constants.hh
diff --git a/include/gz/sim/Constants.hh b/include/gz/sim/Constants.hh
new file mode 100644
index 0000000000..5721eef9ce
--- /dev/null
+++ b/include/gz/sim/Constants.hh
@@ -0,0 +1,39 @@
+/*
+ * 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
+
+namespace gz::sim
+{
+// Inline bracket to help doxygen filtering.
+inline namespace GZ_SIM_VERSION_NAMESPACE
+{
+ namespace config_action {
+ constexpr std::string_view kPluginAttribute{"gz:config_action"};
+ constexpr std::string_view kPrependReplace{"prepend_replace"};
+ constexpr std::string_view kPrepend{"prepend"};
+ constexpr std::string_view kAppendReplace{"append_replace"};
+ constexpr std::string_view kAppend{"append"};
+ }
+}
+} // namespace gz::sim
+
+#endif
From 857d2cfe66b7dc5b310a576d967eb84c02e715fb Mon Sep 17 00:00:00 2001
From: "Addisu Z. Taddese"
Date: Fri, 23 Aug 2024 18:01:44 -0500
Subject: [PATCH 03/15] Change name of parameter
Signed-off-by: Addisu Z. Taddese
---
include/gz/sim/Constants.hh | 3 +++
src/SimulationRunner.cc | 20 ++++++++++----------
src/gui/Gui.cc | 16 ++++++++--------
3 files changed, 21 insertions(+), 18 deletions(-)
diff --git a/include/gz/sim/Constants.hh b/include/gz/sim/Constants.hh
index 5721eef9ce..923c5e09d2 100644
--- a/include/gz/sim/Constants.hh
+++ b/include/gz/sim/Constants.hh
@@ -32,7 +32,10 @@ inline namespace GZ_SIM_VERSION_NAMESPACE
constexpr std::string_view kPrepend{"prepend"};
constexpr std::string_view kAppendReplace{"append_replace"};
constexpr std::string_view kAppend{"append"};
+
}
+
+ constexpr std::string_view kPoliciesTag{"gz:policies"};
}
} // namespace gz::sim
diff --git a/src/SimulationRunner.cc b/src/SimulationRunner.cc
index 6ec6fcfd3f..bdec8c5f47 100644
--- a/src/SimulationRunner.cc
+++ b/src/SimulationRunner.cc
@@ -255,19 +255,19 @@ SimulationRunner::SimulationRunner(const sdf::World *_world,
this->levelMgr->UpdateLevelsState();
auto worldElem = this->sdfWorld->Element();
- bool noDefaultServerPlugins = false;
- bool noDefaultGuiPlugins = false;
+ bool includeDefaultServerPlugins = true;
+ bool includeDefaultGuiPlugins = true;
if (worldElem)
{
- auto policies = worldElem->FindElement("gz:policies");
+ auto policies = worldElem->FindElement(std::string(kPoliciesTag));
if (policies)
{
- noDefaultServerPlugins =
+ includeDefaultServerPlugins =
policies
- ->Get("no_default_server_plugins", noDefaultServerPlugins)
+ ->Get("include_default_server_plugins", includeDefaultServerPlugins)
.first;
- noDefaultGuiPlugins =
- policies->Get("no_default_gui_plugins", noDefaultGuiPlugins)
+ includeDefaultGuiPlugins =
+ policies->Get("include_default_gui_plugins", includeDefaultGuiPlugins)
.first;
}
}
@@ -283,11 +283,11 @@ SimulationRunner::SimulationRunner(const sdf::World *_world,
};
auto combineUserAndDefaultPlugins =
- [](const auto &_userPlugins, const auto &_defaultPlugins, bool _policy)
+ [](const auto &_userPlugins, const auto &_defaultPlugins, bool _includeDefaultPlugins)
{
// TODO(azeey) Handle serverConfigPlugins
/* auto serverConfigPlugins = this->serverConfig.Plugins(); */
- if (!_policy)
+ if (_includeDefaultPlugins)
{
auto combinedPlugins = _defaultPlugins;
for (const auto &userPlugin : _userPlugins)
@@ -331,7 +331,7 @@ SimulationRunner::SimulationRunner(const sdf::World *_world,
// differently
auto pluginsToLoad = combineUserAndDefaultPlugins(
getUserPlugins(), sim::loadPluginInfo(isPlayback),
- noDefaultServerPlugins);
+ includeDefaultServerPlugins);
gzdbg << "Loading plugins:\n";
for (const auto &plugin: pluginsToLoad) {
gzdbg << plugin.Plugin().Name() << "\n";
diff --git a/src/gui/Gui.cc b/src/gui/Gui.cc
index a653954139..738a6dbd6f 100644
--- a/src/gui/Gui.cc
+++ b/src/gui/Gui.cc
@@ -422,7 +422,7 @@ std::unique_ptr createGui(
runner->setParent(gz::gui::App());
++runnerCount;
- bool noDefaultGuiPlugins = false;
+ bool includeDefaultGuiPlugins = false;
std::cout << res.DebugString() << std::endl;
for (const auto &data : res.header().data())
{
@@ -434,19 +434,19 @@ std::unique_ptr createGui(
if (doc.Parse(data.value(0).c_str()) == tinyxml2::XML_SUCCESS)
{
tinyxml2::XMLHandle handle(doc);
- auto elem = handle.FirstChildElement("gz:policies")
- .FirstChildElement("no_default_gui_plugins")
+ auto elem = handle.FirstChildElement(kPoliciesTag.data())
+ .FirstChildElement("include_default_gui_plugins")
.ToElement();
if (elem)
{
- elem->QueryBoolText(&noDefaultGuiPlugins);
+ elem->QueryBoolText(&includeDefaultGuiPlugins);
}
}
}
}
}
- gzmsg << "no_default_gui_plugins: " << noDefaultGuiPlugins << "\n";
+ gzmsg << "include_default_gui_plugins: " << includeDefaultGuiPlugins << "\n";
// Load plugins after creating GuiRunner, so they can access worldName
if (_loadPluginsFromSdf)
{
@@ -533,9 +533,9 @@ std::unique_ptr createGui(
auto combineUserAndDefaultPlugins =
[](std::unique_ptr _userPlugins,
const std::unique_ptr& _defaultPlugins,
- bool _policy)
+ bool _includeDefaultPlugins)
{
- if (!_policy)
+ if (!_includeDefaultPlugins)
{
auto combinedPlugins = std::make_unique();
_defaultPlugins->DeepCopy(combinedPlugins.get());
@@ -612,7 +612,7 @@ std::unique_ptr createGui(
gzwarn << "Default plugins:\n";
printPlugins(*defaultPlugins);
auto pluginsToLoad = combineUserAndDefaultPlugins(
- std::move(userPlugins), defaultPlugins, noDefaultGuiPlugins);
+ std::move(userPlugins), defaultPlugins, includeDefaultGuiPlugins);
gzwarn << "Plugins to load:\n";
printPlugins(*pluginsToLoad);
From 73dcaa319630d26cefe0d7a1264bb17ce59c9723 Mon Sep 17 00:00:00 2001
From: "Addisu Z. Taddese"
Date: Mon, 26 Aug 2024 17:58:36 -0500
Subject: [PATCH 04/15] WIP
Signed-off-by: Addisu Z. Taddese
---
examples/worlds/camera_sensor.sdf | 2 +-
src/SimulationRunner.cc | 180 ++++++++++++++----------------
2 files changed, 85 insertions(+), 97 deletions(-)
diff --git a/examples/worlds/camera_sensor.sdf b/examples/worlds/camera_sensor.sdf
index 50ecfd158b..7d551db60e 100644
--- a/examples/worlds/camera_sensor.sdf
+++ b/examples/worlds/camera_sensor.sdf
@@ -21,7 +21,7 @@
- false
+ true
diff --git a/src/SimulationRunner.cc b/src/SimulationRunner.cc
index 326b31155c..8d6cb0812c 100644
--- a/src/SimulationRunner.cc
+++ b/src/SimulationRunner.cc
@@ -18,7 +18,6 @@
#include "SimulationRunner.hh"
#include
-#include
#ifdef HAVE_PYBIND11
#include
#endif
@@ -246,93 +245,8 @@ SimulationRunner::SimulationRunner(const sdf::World &_world,
// Create the level manager
this->levelMgr = std::make_unique(this,
this->serverConfig.UseLevels());
- auto worldElem = this->sdfWorld->Element();
- bool includeDefaultServerPlugins = true;
- bool includeDefaultGuiPlugins = true;
- if (worldElem)
- {
- auto policies = worldElem->FindElement(std::string(kPoliciesTag));
- if (policies)
- {
- includeDefaultServerPlugins =
- policies
- ->Get("include_default_server_plugins", includeDefaultServerPlugins)
- .first;
- includeDefaultGuiPlugins =
- policies->Get("include_default_gui_plugins", includeDefaultGuiPlugins)
- .first;
- }
- }
- auto getUserPlugins = [&]()
- {
- std::list userPlugins;
- for (const auto &plugin : this->sdfWorld->Plugins())
- {
- userPlugins.emplace_back("*", "world", plugin);
- }
- return userPlugins;
- };
- auto combineUserAndDefaultPlugins =
- [](const auto &_userPlugins, const auto &_defaultPlugins, bool _includeDefaultPlugins)
- {
- // TODO(azeey) Handle serverConfigPlugins
- /* auto serverConfigPlugins = this->serverConfig.Plugins(); */
- if (_includeDefaultPlugins)
- {
- auto combinedPlugins = _defaultPlugins;
- for (const auto &userPlugin : _userPlugins)
- {
- auto pluginElem = userPlugin.Plugin().Element();
- assert(pluginElem);
- auto configAction = pluginElem
- ->template Get("gz:config_action",
- "append_replace")
- .first;
- gzmsg << "Plugin: " << userPlugin.Plugin().Filename() << " act: " << configAction << "\n";
- if (configAction == config_action::kPrependReplace ||
- configAction == config_action::kAppendReplace)
- {
- // Remove all matching plugins
- combinedPlugins.remove_if(
- [&](const auto &_pl) {
- return _pl.Plugin().Filename() ==
- userPlugin.Plugin().Filename();
- });
- }
- if (configAction == config_action::kPrependReplace ||
- configAction == config_action::kPrepend)
- {
- // Remove all matching plugins
- combinedPlugins.push_front(userPlugin);
- }
- else if (configAction == config_action::kAppendReplace ||
- configAction == config_action::kAppend)
- {
- combinedPlugins.push_back(userPlugin);
- }
- }
- return combinedPlugins;
- }
- return _userPlugins;
- };
- bool isPlayback = !this->serverConfig.LogPlaybackPath().empty();
- // TODO(azeey) Let's assume these are just default plugins. loadPluginInfo
- // can also load from a custom config file, so we need to handle that
- // differently
- auto pluginsToLoad = combineUserAndDefaultPlugins(
- getUserPlugins(), sim::loadPluginInfo(isPlayback),
- includeDefaultServerPlugins);
- gzdbg << "Loading plugins:\n";
- for (const auto &plugin: pluginsToLoad) {
- gzdbg << plugin.Plugin().Name() << "\n";
- /* gzdbg << plugin.Plugin().Element()->ToString("\t"); */
- }
this->CreateEntities(_world);
- this->LoadServerPlugins(pluginsToLoad);
- // Store the initial state of the ECM;
- this->initialEntityCompMgr.CopyFrom(this->entityCompMgr);
-
// TODO(louise) Combine both messages into one.
this->node->Advertise("control", &SimulationRunner::OnWorldControl, this);
@@ -350,6 +264,7 @@ SimulationRunner::SimulationRunner(const sdf::World &_world,
if (_world.Gui())
{
this->guiMsg = convert(*_world.Gui());
+ auto worldElem = _world.Element();
if (worldElem)
{
auto policies = worldElem->FindElement("gz:policies");
@@ -1680,18 +1595,91 @@ void SimulationRunner::CreateEntities(const sdf::World &_world)
this->LoadLoggingPlugins(this->serverConfig);
- // Load any additional plugins from the Server Configuration
- this->LoadServerPlugins(this->serverConfig.Plugins());
-
- // 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 includeDefaultServerPlugins = true;
+ bool includeDefaultGuiPlugins = 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)
+ {
+ includeDefaultServerPlugins =
+ policies
+ ->Get("include_default_server_plugins", includeDefaultServerPlugins)
+ .first;
+ includeDefaultGuiPlugins =
+ policies->Get("include_default_gui_plugins", includeDefaultGuiPlugins)
+ .first;
+ }
}
+ auto getUserPlugins = [&]()
+ {
+ std::list userPlugins;
+ for (const auto &plugin : this->sdfWorld.Plugins())
+ {
+ userPlugins.emplace_back("*", "world", plugin);
+ }
+ return userPlugins;
+ };
+ auto combineUserAndDefaultPlugins =
+ [](const auto &_userPlugins, const auto &_defaultPlugins, bool _includeDefaultPlugins)
+ {
+ // TODO(azeey) Handle serverConfigPlugins
+ /* auto serverConfigPlugins = this->serverConfig.Plugins(); */
+ if (_includeDefaultPlugins)
+ {
+ auto combinedPlugins = _defaultPlugins;
+ for (const auto &userPlugin : _userPlugins)
+ {
+ auto pluginElem = userPlugin.Plugin().Element();
+ assert(pluginElem);
+ auto configAction = pluginElem
+ ->template Get("gz:config_action",
+ "append_replace")
+ .first;
+ gzmsg << "Plugin: " << userPlugin.Plugin().Filename() << " act: " << configAction << "\n";
+ if (configAction == config_action::kPrependReplace ||
+ configAction == config_action::kAppendReplace)
+ {
+ // Remove all matching plugins
+ combinedPlugins.remove_if(
+ [&](const auto &_pl) {
+ return _pl.Plugin().Filename() ==
+ userPlugin.Plugin().Filename();
+ });
+ }
+ if (configAction == config_action::kPrependReplace ||
+ configAction == config_action::kPrepend)
+ {
+ // Remove all matching plugins
+ combinedPlugins.push_front(userPlugin);
+ }
+ else if (configAction == config_action::kAppendReplace ||
+ configAction == config_action::kAppend)
+ {
+ combinedPlugins.push_back(userPlugin);
+ }
+ }
+ return combinedPlugins;
+ }
+ return _userPlugins;
+ };
+ bool isPlayback = !this->serverConfig.LogPlaybackPath().empty();
+ // TODO(azeey) Let's assume these are just default plugins. loadPluginInfo
+ // can also load from a custom config file, so we need to handle that
+ // differently
+ auto pluginsToLoad = combineUserAndDefaultPlugins(
+ getUserPlugins(), sim::loadPluginInfo(isPlayback),
+ includeDefaultServerPlugins);
+ gzdbg << "Loading plugins:\n";
+ for (const auto &plugin: pluginsToLoad) {
+ gzdbg << plugin.Plugin().Name() << "\n";
+ /* gzdbg << plugin.Plugin().Element()->ToString("\t"); */
+ }
+
+ // Load server plugins from a combination of default and user specified
+ // plugins
+ this->LoadServerPlugins(pluginsToLoad);
// Store the initial state of the ECM;
this->initialEntityCompMgr.CopyFrom(this->entityCompMgr);
From 7c6e8b7e647b70d481cf751e5df44fecb383d7fc Mon Sep 17 00:00:00 2001
From: "Addisu Z. Taddese"
Date: Tue, 27 Aug 2024 14:35:29 -0500
Subject: [PATCH 05/15] Simplify behavior by only supporting append_replace
Signed-off-by: Addisu Z. Taddese
---
src/SimulationRunner.cc | 130 ++++++++++++++++------------------------
1 file changed, 51 insertions(+), 79 deletions(-)
diff --git a/src/SimulationRunner.cc b/src/SimulationRunner.cc
index 8d6cb0812c..abd0717b4a 100644
--- a/src/SimulationRunner.cc
+++ b/src/SimulationRunner.cc
@@ -18,6 +18,7 @@
#include "SimulationRunner.hh"
#include
+#include "gz/sim/ServerConfig.hh"
#ifdef HAVE_PYBIND11
#include
#endif
@@ -264,17 +265,6 @@ SimulationRunner::SimulationRunner(const sdf::World &_world,
if (_world.Gui())
{
this->guiMsg = convert(*_world.Gui());
- auto worldElem = _world.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"};
@@ -1595,91 +1585,62 @@ void SimulationRunner::CreateEntities(const sdf::World &_world)
this->LoadLoggingPlugins(this->serverConfig);
+ // 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.
+
auto worldElem = this->sdfWorld.Element();
bool includeDefaultServerPlugins = true;
- bool includeDefaultGuiPlugins = true;
if (worldElem)
{
auto policies = worldElem->FindElement(std::string(kPoliciesTag));
if (policies)
{
includeDefaultServerPlugins =
- policies
- ->Get("include_default_server_plugins", includeDefaultServerPlugins)
- .first;
- includeDefaultGuiPlugins =
- policies->Get("include_default_gui_plugins", includeDefaultGuiPlugins)
- .first;
+ policies
+ ->Get("include_default_server_plugins", includeDefaultServerPlugins)
+ .first;
}
}
- auto getUserPlugins = [&]()
+
+ if (includeDefaultServerPlugins || loadedWorldPlugins.empty())
{
- std::list userPlugins;
- for (const auto &plugin : this->sdfWorld.Plugins())
+ bool isPlayback = !this->serverConfig.LogPlaybackPath().empty();
+ auto defaultPlugins = gz::sim::loadPluginInfo(isPlayback);
+ if (loadedWorldPlugins.empty())
{
- userPlugins.emplace_back("*", "world", plugin);
+ gzmsg << "No systems loaded from SDF, loading defaults" << std::endl;
}
- return userPlugins;
- };
- auto combineUserAndDefaultPlugins =
- [](const auto &_userPlugins, const auto &_defaultPlugins, bool _includeDefaultPlugins)
- {
- // TODO(azeey) Handle serverConfigPlugins
- /* auto serverConfigPlugins = this->serverConfig.Plugins(); */
- if (_includeDefaultPlugins)
+ else
{
- auto combinedPlugins = _defaultPlugins;
- for (const auto &userPlugin : _userPlugins)
+ auto isPluginLoaded =
+ [&loadedWorldPlugins](const ServerConfig::PluginInfo &_pl)
{
- auto pluginElem = userPlugin.Plugin().Element();
- assert(pluginElem);
- auto configAction = pluginElem
- ->template Get("gz:config_action",
- "append_replace")
- .first;
- gzmsg << "Plugin: " << userPlugin.Plugin().Filename() << " act: " << configAction << "\n";
- if (configAction == config_action::kPrependReplace ||
- configAction == config_action::kAppendReplace)
- {
- // Remove all matching plugins
- combinedPlugins.remove_if(
- [&](const auto &_pl) {
- return _pl.Plugin().Filename() ==
- userPlugin.Plugin().Filename();
- });
- }
- if (configAction == config_action::kPrependReplace ||
- configAction == config_action::kPrepend)
- {
- // Remove all matching plugins
- combinedPlugins.push_front(userPlugin);
- }
- else if (configAction == config_action::kAppendReplace ||
- configAction == config_action::kAppend)
- {
- combinedPlugins.push_back(userPlugin);
- }
+ auto it = std::find_if(
+ loadedWorldPlugins.begin(), loadedWorldPlugins.end(),
+ [&_pl](const auto &_worldPlugin)
+ { return _worldPlugin.fname == _pl.Plugin().Filename(); });
+
+ return it != loadedWorldPlugins.end();
+ };
+
+ // Remove plugin if it's already loaded so as to not duplicate world
+ // plugins.
+ defaultPlugins.remove_if(isPluginLoaded);
+
+ gzdbg << "Also loading the following default jplugins:\n";
+ for (const auto &plugin : defaultPlugins)
+ {
+ gzdbg << plugin.Plugin().Name() << " " << plugin.Plugin().Filename() << "\n";
+ /* gzdbg << plugin.Plugin().Element()->ToString("\t"); */
}
- return combinedPlugins;
}
- return _userPlugins;
- };
- bool isPlayback = !this->serverConfig.LogPlaybackPath().empty();
- // TODO(azeey) Let's assume these are just default plugins. loadPluginInfo
- // can also load from a custom config file, so we need to handle that
- // differently
- auto pluginsToLoad = combineUserAndDefaultPlugins(
- getUserPlugins(), sim::loadPluginInfo(isPlayback),
- includeDefaultServerPlugins);
- gzdbg << "Loading plugins:\n";
- for (const auto &plugin: pluginsToLoad) {
- gzdbg << plugin.Plugin().Name() << "\n";
- /* gzdbg << plugin.Plugin().Element()->ToString("\t"); */
- }
- // Load server plugins from a combination of default and user specified
- // plugins
- this->LoadServerPlugins(pluginsToLoad);
+ this->LoadServerPlugins(defaultPlugins);
+ };
// Store the initial state of the ECM;
this->initialEntityCompMgr.CopyFrom(this->entityCompMgr);
@@ -1687,5 +1648,16 @@ void SimulationRunner::CreateEntities(const sdf::World &_world)
// 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(*_world.Gui());
+ {
+ 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(""));
+ }
+ }
+ }
}
From 64d2d95c68d1fabb5fb32829cfb24ff25d6e9188 Mon Sep 17 00:00:00 2001
From: "Addisu Z. Taddese"
Date: Tue, 27 Aug 2024 14:41:02 -0500
Subject: [PATCH 06/15] Revert some examples
Signed-off-by: Addisu Z. Taddese
---
examples/worlds/empty.sdf | 11 ++++++++---
examples/worlds/shapes.sdf | 10 ----------
src/SimulationRunner.cc | 18 +++++++++---------
src/gui/Gui.cc | 7 +++----
4 files changed, 20 insertions(+), 26 deletions(-)
diff --git a/examples/worlds/empty.sdf b/examples/worlds/empty.sdf
index aa08b76fcc..3f0ad8dfda 100644
--- a/examples/worlds/empty.sdf
+++ b/examples/worlds/empty.sdf
@@ -65,14 +65,19 @@ gz service -s /world/empty/create \
0.001
1.0
-
- bullet
+
+
+
+
diff --git a/examples/worlds/shapes.sdf b/examples/worlds/shapes.sdf
index ecdc64bce0..5d020a8c32 100644
--- a/examples/worlds/shapes.sdf
+++ b/examples/worlds/shapes.sdf
@@ -9,16 +9,6 @@
--timeout 300 --req 'name: "box", position: {z: 5.0}'
]]>
-
- true
-
-
- prepend_replace
- gz-physics-bullet-featherstone-plugin
-
-
- append
-
1.0 1.0 1.0
0.8 0.8 0.8
diff --git a/src/SimulationRunner.cc b/src/SimulationRunner.cc
index abd0717b4a..358655dc81 100644
--- a/src/SimulationRunner.cc
+++ b/src/SimulationRunner.cc
@@ -18,7 +18,7 @@
#include "SimulationRunner.hh"
#include
-#include "gz/sim/ServerConfig.hh"
+#include
#ifdef HAVE_PYBIND11
#include
#endif
@@ -52,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"
@@ -1616,15 +1617,15 @@ void SimulationRunner::CreateEntities(const sdf::World &_world)
}
else
{
+ std::unordered_set loadedWorldPluginFileNames;
+ for (const auto &pl : loadedWorldPlugins)
+ {
+ loadedWorldPluginFileNames.insert(pl.fname);
+ }
auto isPluginLoaded =
- [&loadedWorldPlugins](const ServerConfig::PluginInfo &_pl)
+ [&loadedWorldPluginFileNames](const ServerConfig::PluginInfo &_pl)
{
- auto it = std::find_if(
- loadedWorldPlugins.begin(), loadedWorldPlugins.end(),
- [&_pl](const auto &_worldPlugin)
- { return _worldPlugin.fname == _pl.Plugin().Filename(); });
-
- return it != loadedWorldPlugins.end();
+ return loadedWorldPluginFileNames.count(_pl.Plugin().Filename()) != 0;
};
// Remove plugin if it's already loaded so as to not duplicate world
@@ -1635,7 +1636,6 @@ void SimulationRunner::CreateEntities(const sdf::World &_world)
for (const auto &plugin : defaultPlugins)
{
gzdbg << plugin.Plugin().Name() << " " << plugin.Plugin().Filename() << "\n";
- /* gzdbg << plugin.Plugin().Element()->ToString("\t"); */
}
}
diff --git a/src/gui/Gui.cc b/src/gui/Gui.cc
index 14f2913cf8..7220468199 100644
--- a/src/gui/Gui.cc
+++ b/src/gui/Gui.cc
@@ -405,11 +405,11 @@ std::unique_ptr createGui(
result = false;
gz::msgs::GUI res;
service = transport::TopicUtils::AsValidTopic("/world/" + worldName +
- "/gui/info");
+ "/gui/info");
if (service.empty())
{
gzerr << "Failed to generate valid service for world [" << worldName
- << "]" << std::endl;
+ << "]" << std::endl;
}
else
{
@@ -421,7 +421,7 @@ std::unique_ptr createGui(
if (!executed)
{
gzerr << "Service call timed out for [" << service << "]"
- << std::endl;
+ << std::endl;
}
else if (!result)
{
@@ -435,7 +435,6 @@ std::unique_ptr createGui(
++runnerCount;
bool includeDefaultGuiPlugins = false;
- std::cout << res.DebugString() << std::endl;
for (const auto &data : res.header().data())
{
if (data.key() == "gz:policies")
From 64c3eb1b04a4d7db4725bb062f55e5a4cfbb0603 Mon Sep 17 00:00:00 2001
From: "Addisu Z. Taddese"
Date: Tue, 27 Aug 2024 20:13:43 -0500
Subject: [PATCH 07/15] Update server_config tutorial, change name of policy
parameter
Signed-off-by: Addisu Z. Taddese
---
src/SimulationRunner.cc | 8 +--
tutorials/server_config.md | 112 ++++++++++++++++++++++++++++++++++---
2 files changed, 108 insertions(+), 12 deletions(-)
diff --git a/src/SimulationRunner.cc b/src/SimulationRunner.cc
index 358655dc81..a297093457 100644
--- a/src/SimulationRunner.cc
+++ b/src/SimulationRunner.cc
@@ -1594,20 +1594,20 @@ void SimulationRunner::CreateEntities(const sdf::World &_world)
// load a default set of systems.
auto worldElem = this->sdfWorld.Element();
- bool includeDefaultServerPlugins = true;
+ bool includeServerConfigPlugins = true;
if (worldElem)
{
auto policies = worldElem->FindElement(std::string(kPoliciesTag));
if (policies)
{
- includeDefaultServerPlugins =
+ includeServerConfigPlugins =
policies
- ->Get("include_default_server_plugins", includeDefaultServerPlugins)
+ ->Get("include_server_config_plugins", includeServerConfigPlugins)
.first;
}
}
- if (includeDefaultServerPlugins || loadedWorldPlugins.empty())
+ if (includeServerConfigPlugins || loadedWorldPlugins.empty())
{
bool isPlayback = !this->serverConfig.LogPlaybackPath().empty();
auto defaultPlugins = gz::sim::loadPluginInfo(isPlayback);
diff --git a/tutorials/server_config.md b/tutorials/server_config.md
index bbab5f5110..72dd2ba78e 100644
--- a/tutorials/server_config.md
+++ b/tutorials/server_config.md
@@ -17,11 +17,26 @@ There are a few places where the plugins can be defined:
3. The default configuration file at `$HOME/.gz/sim/<#>/server.config` \*,
where `<#>` is Gazebo Sim's major version.
-Each of the items above takes precedence over the ones below it. For example,
-if a the SDF file has any `` elements, then the
-`GZ_SIM_SERVER_CONFIG_PATH` variable is ignored. And the default configuration
-file is only loaded if no plugins are passed through the SDF file or the
-environment variable.
+The behavior of Gazebo when loading these plugins depends on the
+``policy set in ``:
+
+- `true`: Plugins
+ in the SDF file are first loaded, followed by plugins from config files
+ (either `GZ_SIM_SERVER_CONFIG_PATH` or the default configuration file).
+ Plugins from SDF files take precedence over plugins from config files, this
+ means, if a plugin is specified in both places, only the one specified in the
+ SDF file will be loaded. The main use case for this is for users to rely on
+ the default list of plugins and only add extra plugins they need for the
+ application. This is the default setting in Gazebo Ionic and later.
+
+- `false`: If
+ there are any plugins specified in the SDF file, plugins from the config files
+ (either `GZ_SIM_SERVER_CONFIG_PATH` or the default configuration file) are
+ ignored. This allows the user to have complete control over which plugins are
+ loaded. This is the default setting in Gazebo Harmonic and earlier.
+
+In both policy settings, the default configuration file is only loaded if no
+plugins are passed through the `GZ_SIM_SERVER_CONFIG_PATH` environment variable.
> \* For log-playback, the default file is
> `$HOME/.gz/sim/<#>/playback_server.config`
@@ -85,7 +100,7 @@ will be created with default values:
Let's try overriding the default configuration from an SDF file. Open your
favorite editor and save this file as `fuel_preview.sdf`:
-```
+```xml
@@ -147,8 +162,84 @@ Now let's load this world:
`gz sim -r /fuel_preview.sdf`
-Notice how the application has only one system plugin loaded, the scene
-broadcaster, as defined on the SDF file above. Physics is not loaded, so even
+Notice how the application has loaded the scene
+broadcaster, as defined on the SDF file above as well as the default plugins
+`Physics` and `UserCommands`. Since `SceneBroadcaster` is loaded from the SDF file,
+it's not loaded again. We see that the cone falls due to gravity since all the
+necessary plugins are loaded.
+
+@image html files/server_config/from_sdf_no_plugins.gif
+
+Now, let's modify the SDF file to change the policy `false`
+
+```xml
+
+
+
+
+
+ false
+
+
+
+
+
+
+
+
+
+
+ 3D View
+ false
+ docked
+
+
+ ogre2
+ scene
+ 1.0 1.0 1.0
+ 0.4 0.6 1.0
+ 8.3 7 7.8 0 0.5 -2.4
+
+
+
+ false
+ 5
+ 5
+ floating
+ false
+
+
+
+
+ false
+ 5
+ 5
+ floating
+ false
+
+
+
+
+
+
+ https://fuel.gazebosim.org/1.0/OpenRobotics/models/Sun
+
+
+
+ https://fuel.gazebosim.org/1.0/OpenRobotics/models/Construction Cone
+
+
+
+
+```
+Let's load this world again:
+
+`gz sim -r /fuel_preview.sdf`
+
+Notice how the application has only one system plugin loaded, the `SceneBroadcaster`,
+as defined on the SDF file above. `Physics` is not loaded, so even
though the simulation is running (started with `-r`), the cone doesn't fall
with gravity.
@@ -299,3 +390,8 @@ the background color is the default grey, instead of the blue color set on the
GUI `GzScene` plugin.
@image html files/server_config/camera_env.gif
+
+
+### Order of Execution of Plugins
+The order of execution of plugins can be controlled by setting
+the `` tag inside ``. See example in examples/plugin/priority_printer_plugin and the associated README.md file to learn more.
From 96591c9fcc0257d8790bf3588868cb2d4bccd8fc Mon Sep 17 00:00:00 2001
From: "Addisu Z. Taddese"
Date: Wed, 28 Aug 2024 00:38:36 -0500
Subject: [PATCH 08/15] Add some content to GUI tutorial
Signed-off-by: Addisu Z. Taddese
---
include/gz/sim/Constants.hh | 2 +-
src/SimulationRunner.cc | 3 +-
src/gui/Gui.cc | 396 ++++++++++++++++++++----------------
tutorials/gui_config.md | 54 ++++-
tutorials/server_config.md | 2 +-
5 files changed, 269 insertions(+), 188 deletions(-)
diff --git a/include/gz/sim/Constants.hh b/include/gz/sim/Constants.hh
index 923c5e09d2..21f228a2fc 100644
--- a/include/gz/sim/Constants.hh
+++ b/include/gz/sim/Constants.hh
@@ -32,7 +32,7 @@ inline namespace GZ_SIM_VERSION_NAMESPACE
constexpr std::string_view kPrepend{"prepend"};
constexpr std::string_view kAppendReplace{"append_replace"};
constexpr std::string_view kAppend{"append"};
-
+ constexpr std::string_view kGuiDefaultAction{kAppendReplace};
}
constexpr std::string_view kPoliciesTag{"gz:policies"};
diff --git a/src/SimulationRunner.cc b/src/SimulationRunner.cc
index a297093457..aceb05360d 100644
--- a/src/SimulationRunner.cc
+++ b/src/SimulationRunner.cc
@@ -1635,7 +1635,8 @@ void SimulationRunner::CreateEntities(const sdf::World &_world)
gzdbg << "Also loading the following default jplugins:\n";
for (const auto &plugin : defaultPlugins)
{
- gzdbg << plugin.Plugin().Name() << " " << plugin.Plugin().Filename() << "\n";
+ gzdbg << plugin.Plugin().Name() << " " << plugin.Plugin().Filename()
+ << "\n";
}
}
diff --git a/src/gui/Gui.cc b/src/gui/Gui.cc
index 7220468199..a3d4c354e2 100644
--- a/src/gui/Gui.cc
+++ b/src/gui/Gui.cc
@@ -50,6 +50,173 @@ namespace sim
{
// Inline bracket to help doxygen filtering.
inline namespace GZ_SIM_VERSION_NAMESPACE {
+namespace {
+
+std::unique_ptr parseDefaultPlugins(
+ const std::string &_defaultConfig)
+{
+ const auto resolvedDefaultConfigPath =
+ gz::gui::App()->ResolveConfigFile(_defaultConfig);
+ auto pluginsDoc = std::make_unique();
+ if (pluginsDoc->LoadFile(resolvedDefaultConfigPath.c_str()) ==
+ tinyxml2::XML_SUCCESS)
+ {
+ // Remove everything that's not a plugin
+ for (auto elem = pluginsDoc->FirstChildElement(); elem != nullptr;)
+ {
+ if (std::strcmp("plugin", elem->Value()) != 0)
+ {
+ auto tmp = elem;
+ elem = elem->NextSiblingElement();
+ pluginsDoc->DeleteChild(tmp);
+ }
+ else
+ {
+ elem = elem->NextSiblingElement();
+ }
+ }
+ }
+
+ return pluginsDoc;
+}
+
+auto combineUserAndDefaultPlugins(
+ std::unique_ptr _userPlugins,
+ const tinyxml2::XMLDocument &_defaultPlugins, bool _includeDefaultPlugins)
+{
+ if (!_includeDefaultPlugins)
+ {
+ auto combinedPlugins = std::make_unique();
+ _defaultPlugins.DeepCopy(combinedPlugins.get());
+
+ tinyxml2::XMLDocument prependList;
+ tinyxml2::XMLDocument appendList;
+ for (auto pluginElem = _userPlugins->FirstChildElement("plugin");
+ pluginElem != nullptr;
+ pluginElem = pluginElem->NextSiblingElement("plugin"))
+ {
+ const char *pluginFilename = pluginElem->Attribute("filename");
+ std::string configAction = "";
+
+ auto configActionElement =
+ pluginElem->FirstChildElement(config_action::kPluginAttribute.data());
+ if (configActionElement)
+ {
+ configAction = configActionElement->GetText();
+ }
+
+ if (configAction == "")
+ {
+ configAction = config_action::kGuiDefaultAction;
+ }
+
+ gzdbg << "Plugin: " << pluginFilename << " act: " << configAction << "\n";
+
+ if (configAction == config_action::kPrependReplace ||
+ configAction == config_action::kAppendReplace)
+ {
+ // Remove all matching plugins
+ for (auto elem = combinedPlugins->FirstChildElement("plugin");
+ elem != nullptr;)
+ {
+ if (elem->Attribute("filename", pluginFilename))
+ {
+ gzdbg << "\t Removing " << pluginFilename << "\n";
+ auto tmp = elem;
+ elem = elem->NextSiblingElement("plugin");
+ combinedPlugins->DeleteNode(tmp);
+ }
+ else
+ {
+ elem = elem->NextSiblingElement("plugin");
+ }
+ }
+ }
+ if (configAction == config_action::kPrependReplace ||
+ configAction == config_action::kPrepend)
+ {
+ auto clonedPlugin = pluginElem->DeepClone(&prependList);
+ prependList.InsertEndChild(clonedPlugin);
+ }
+ else if (configAction == config_action::kAppendReplace ||
+ configAction == config_action::kAppend)
+ {
+ auto clonedPlugin = pluginElem->DeepClone(&appendList);
+ appendList.InsertEndChild(clonedPlugin);
+ }
+ else
+ {
+ gzerr << "Unknown config action: " << configAction << std::endl;
+ }
+ }
+
+ // At this point, combinedPlugins has been cleared of duplicate plugins
+ // and prependList and appendList contain the list of plugins to be
+ // prepended and appended respectively in the correct order.
+ tinyxml2::XMLNode *lastInsertedNode = nullptr;
+ for (auto pluginElem = prependList.FirstChildElement();
+ pluginElem != nullptr; pluginElem = pluginElem->NextSiblingElement())
+ {
+ auto clonedPlugin = pluginElem->DeepClone(combinedPlugins.get());
+ if (lastInsertedNode == nullptr)
+ {
+ lastInsertedNode = combinedPlugins->InsertFirstChild(clonedPlugin);
+ }
+ else
+ {
+ combinedPlugins->InsertAfterChild(lastInsertedNode, clonedPlugin);
+ }
+ }
+
+ for (auto pluginElem = appendList.FirstChildElement();
+ pluginElem != nullptr; pluginElem = pluginElem->NextSiblingElement())
+ {
+ auto clonedPlugin = pluginElem->DeepClone(combinedPlugins.get());
+ combinedPlugins->InsertEndChild(clonedPlugin);
+ }
+
+ return combinedPlugins;
+ }
+ return _userPlugins;
+}
+
+/// \brief Various policies that affect the behavior of the GUI
+struct GuiPolicies
+{
+ /// \brief Whether to include default plugins
+ bool includeGuiDefaultPlugins{false};
+
+ /// \brief Parse policies from a GUI message
+ /// \param[in] _msg Input message
+ /// \return A GuiPolicies object populated from parsing the message.
+ static GuiPolicies ParsePolicies(const msgs::GUI &_msg)
+ {
+ GuiPolicies policies;
+ for (const auto &data : _msg.header().data())
+ {
+ if (data.key() == "gz:policies")
+ {
+ tinyxml2::XMLDocument doc;
+ if (data.value_size() > 0)
+ {
+ if (doc.Parse(data.value(0).c_str()) == tinyxml2::XML_SUCCESS)
+ {
+ tinyxml2::XMLHandle handle(doc);
+ auto elem = handle.FirstChildElement(kPoliciesTag.data())
+ .FirstChildElement("include_gui_default_plugins")
+ .ToElement();
+ if (elem)
+ {
+ elem->QueryBoolText(&policies.includeGuiDefaultPlugins);
+ }
+ }
+ }
+ }
+ }
+ return policies;
+ }
+};
+}
namespace gui
{
/// \brief Get the path to the default config file. If the file doesn't exist
@@ -434,200 +601,67 @@ std::unique_ptr createGui(
runner->setParent(gz::gui::App());
++runnerCount;
- bool includeDefaultGuiPlugins = false;
- for (const auto &data : res.header().data())
- {
- if (data.key() == "gz:policies")
- {
- tinyxml2::XMLDocument doc;
- if (data.value_size() > 0)
- {
- if (doc.Parse(data.value(0).c_str()) == tinyxml2::XML_SUCCESS)
- {
- tinyxml2::XMLHandle handle(doc);
- auto elem = handle.FirstChildElement(kPoliciesTag.data())
- .FirstChildElement("include_default_gui_plugins")
- .ToElement();
- if (elem)
- {
- elem->QueryBoolText(&includeDefaultGuiPlugins);
- }
- }
- }
- }
- }
-
- gzmsg << "include_default_gui_plugins: " << includeDefaultGuiPlugins << "\n";
// Load plugins after creating GuiRunner, so they can access worldName
if (_loadPluginsFromSdf)
{
- auto getUserPlugins = [&]()
+ const auto guiPolicies = GuiPolicies::ParsePolicies(res);
+ auto userPlugins = std::make_unique();
+ std::string pluginsXml = "";
+ for (int p = 0; p < res.plugin_size(); ++p)
{
- auto userPluginsDoc = std::make_unique();
- std::string pluginsXml = "";
- for (int p = 0; p < res.plugin_size(); ++p)
- {
- const auto &plugin = res.plugin(p);
- auto fileName = plugin.filename();
- // Redirect GzScene3D to MinimalScene for backwards compatibility,
- // with warnings
- if (fileName == "GzScene3D")
- {
- std::vector extras{
- "GzSceneManager", "InteractiveViewControl",
- "CameraTracking", "MarkerManager",
- "SelectEntities", "EntityContextMenuPlugin",
- "Spawn", "VisualizationCapabilities"};
-
- std::string msg{
- "The [GzScene3D] GUI plugin has been removed since Garden.\n"
- "SDF code to replace GzScene3D is available at "
- "https://github.com/gazebosim/gz-sim/blob/gz-sim7/"
- "Migration.md\n"
- "Loading the following plugins instead:\n"};
-
- for (auto extra : extras)
- {
- msg += "* " + extra + "\n";
-
- auto newPlugin = res.add_plugin();
- newPlugin->set_filename(extra);
- newPlugin->set_innerxml(std::string(
- ""
- " floating"
- " 5"
- " 5"
- " false"
- " false"
- ""));
- }
-
- gzwarn << msg;
-
- fileName = "MinimalScene";
- }
- pluginsXml += "" +
- plugin.innerxml() + "\n";
- }
- userPluginsDoc->Parse(pluginsXml.c_str());
- return userPluginsDoc;
- };
+ const auto &plugin = res.plugin(p);
+ auto fileName = plugin.filename();
- auto getDefaultPlugins = [&]()
- {
- const auto resolvedDefaultConfigPath =
- app->ResolveConfigFile(defaultConfig);
- auto pluginsDoc = std::make_unique();
- if (pluginsDoc->LoadFile(resolvedDefaultConfigPath.c_str()) ==
- tinyxml2::XML_SUCCESS)
+ // Redirect GzScene3D to MinimalScene for backwards compatibility,
+ // with warnings
+ if (fileName == "GzScene3D")
{
- // Remove everything that's not a plugin
- for (auto elem = pluginsDoc->FirstChildElement(); elem != nullptr;)
+ std::vector extras{"GzSceneManager",
+ "InteractiveViewControl",
+ "CameraTracking",
+ "MarkerManager",
+ "SelectEntities",
+ "EntityContextMenuPlugin",
+ "Spawn",
+ "VisualizationCapabilities"};
+
+ std::string msg{
+ "The [GzScene3D] GUI plugin has been removed since Garden.\n"
+ "SDF code to replace GzScene3D is available at "
+ "https://github.com/gazebosim/gz-sim/blob/gz-sim7/Migration.md\n"
+ "Loading the following plugins instead:\n"};
+
+ for (auto extra : extras)
{
- if (std::strcmp("plugin", elem->Value()) != 0)
- {
- auto tmp = elem;
- elem = elem->NextSiblingElement();
- pluginsDoc->DeleteChild(tmp);
- }
- else
- {
- elem = elem->NextSiblingElement();
- }
+ msg += "* " + extra + "\n";
+
+ auto newPlugin = res.add_plugin();
+ newPlugin->set_filename(extra);
+ newPlugin->set_innerxml(std::string(
+ ""
+ " floating"
+ " 5"
+ " 5"
+ " false"
+ " false"
+ ""));
}
- }
- return pluginsDoc;
- };
+ gzwarn << msg;
- auto combineUserAndDefaultPlugins =
- [](std::unique_ptr _userPlugins,
- const std::unique_ptr& _defaultPlugins,
- bool _includeDefaultPlugins)
- {
- if (!_includeDefaultPlugins)
- {
- auto combinedPlugins = std::make_unique();
- _defaultPlugins->DeepCopy(combinedPlugins.get());
- for (auto pluginElem = _userPlugins->FirstChildElement("plugin");
- pluginElem != nullptr;
- pluginElem = pluginElem->NextSiblingElement("plugin"))
- {
- const char *pluginFilename = pluginElem->Attribute("filename");
- std::string configAction = "";
-
- auto configActionElement = pluginElem->FirstChildElement(config_action::kPluginAttribute.data());
- if (configActionElement)
- {
- configAction = configActionElement->GetText();
- }
-
- if (configAction == "")
- {
- configAction = config_action::kAppendReplace;
- }
-
- gzmsg << "Plugin: " << pluginFilename << " act: " << configAction << "\n";
-
- if (configAction == config_action::kPrependReplace ||
- configAction == config_action::kAppendReplace)
- {
- // Remove all matching plugins
- for (auto elem = combinedPlugins->FirstChildElement("plugin");
- elem != nullptr;)
- {
- if (elem->Attribute("filename", pluginFilename))
- {
- gzmsg << "\t Removing " << pluginFilename << "\n";
- auto tmp = elem;
- elem = elem->NextSiblingElement("plugin");
- combinedPlugins->DeleteNode(tmp);
- }
- else
- {
- elem = elem->NextSiblingElement("plugin");
- }
- }
- }
- auto clonedPlugin = pluginElem->DeepClone(combinedPlugins.get());
- if (configAction == config_action::kPrependReplace ||
- configAction == config_action::kPrepend)
- {
- combinedPlugins->InsertFirstChild(clonedPlugin);
- }
- else if (configAction == config_action::kAppendReplace ||
- configAction == config_action::kAppend)
- {
- combinedPlugins->InsertEndChild(clonedPlugin);
- }
- else {
- gzerr << "Unknown config action: " << configAction << std::endl;
- }
- }
- return combinedPlugins;
+ fileName = "MinimalScene";
}
- return _userPlugins;
- };
- auto printPlugins = [](const tinyxml2::XMLDocument &_plugins)
- {
- tinyxml2::XMLPrinter printer;
- _plugins.Print( &printer );
- gzdbg << printer.CStr() << std::endl;
- };
-
- auto userPlugins = getUserPlugins();
- gzwarn << "User plugins:\n";
- printPlugins(*userPlugins);
- auto defaultPlugins = getDefaultPlugins();
- gzwarn << "Default plugins:\n";
- printPlugins(*defaultPlugins);
+ pluginsXml += "" +
+ plugin.innerxml() + "\n";
+ }
+ userPlugins->Parse(pluginsXml.c_str());
+
+ const auto defaultPlugins = parseDefaultPlugins(defaultConfig);
auto pluginsToLoad = combineUserAndDefaultPlugins(
- std::move(userPlugins), defaultPlugins, includeDefaultGuiPlugins);
- gzwarn << "Plugins to load:\n";
- printPlugins(*pluginsToLoad);
+ std::move(userPlugins), *defaultPlugins,
+ guiPolicies.includeGuiDefaultPlugins);
- gzwarn << "Loading plugins:\n";
+ gzdbg << "Loading plugins:\n";
for (auto pluginElem = pluginsToLoad->FirstChildElement("plugin");
pluginElem != nullptr;
pluginElem = pluginElem->NextSiblingElement("plugin"))
diff --git a/tutorials/gui_config.md b/tutorials/gui_config.md
index 9cc42fa1e0..310960d3b0 100644
--- a/tutorials/gui_config.md
+++ b/tutorials/gui_config.md
@@ -16,10 +16,54 @@ There are a few places where the GUI configuration can come from:
3. The default configuration file at `$HOME/.gz/sim/<#>/gui.config` \*,
where `<#>` is Gazebo Sim's major version.
-Each of the items above takes precedence over the ones below it. For example,
-if a user chooses a `--gui-config`, the SDF's `` element is ignored. And
-the default configuration file is only loaded if no configuration is passed
-through the command line or the SDF file.
+If a configuration file is specified using `--gui-config`, Gazebo will
+ignore both the `` element inside the SDF file and the default
+configuration file. Otherwise, Gazebo will load plugins by combining
+plugins in the `` element and the default configuration file.
+How Gazebo combines these plugins is determined by the
+`` policy set in ``:
+
+- `true`: Plugins
+ from the default configuration file merged with plugins from the SDF file.
+ Plugins from SDF files take precedence over plugins from
+ the default configuration file. This means, if a plugin is specified in
+ both places, by default, only the one specified in the SDF file will be
+ loaded. However, plugins in the SDF file can specify how they should be loaded
+ by setting `` tag inside each ``.
+ Four options are available:
+ - `append_replace` (default): The plugin from the SDF file is appended to the
+ list of plugins to be loaded. Any plugin from the default configuration file
+ with the same file name will be removed.
+ - `append`: The plugin from the SDF file is appended to the list of plugins
+ to be loaded. Any plugin from the default configuration file with the same
+ file name will also be loaded. This is useful for some plugins where it makes sense
+ to have two or more of (e.g. `ImageDispay`).
+ - `prepend_replace`: The plugin from the SDF file is prepended to the
+ list of plugins to be loaded. Any plugin from the default configuration file
+ with the same file name will be removed. A typical use of this option is
+ when overriding the settings of `MinimalScene` plugin since it
+ needs to appear first in the list of plugins for the 3D scene to occupy the large
+ pane on the left side of the GUI.
+ - `append`: The plugin from the SDF file is prepended to the list of plugins
+ to be loaded. Any plugin from the default configuration file with the same
+ file name will also be loaded.
+
+ The four options can be classified into two categories based on whether
+ they append or prepend to the list. Within each category, the plugins
+ will keep the order in which they are specified in the SDF file.
+
+ The main use case for this policy is for users to rely on
+ the default list of plugins and only add extra plugins they need for the
+ application. This policy is also useful for overriding the parameters of a small
+ subset of the default plugins.
+
+ This is the default setting of this policy in Gazebo Ionic and later.
+
+- `false`: If
+ there are any plugins specified in the SDF file, plugins from the default
+ configuration file are ignored. This allows the user to have complete
+ control over which plugins are loaded. This is the default setting in
+ Gazebo Harmonic and earlier.
> \* For log-playback, the default file is
> `$HOME/.gz/sim/<#>/playback_gui.config`
@@ -137,6 +181,8 @@ Now let's load this world:
`gz sim /fuel_preview.sdf`
+With the default policy,
+
Notice how the application has only one GUI plugin loaded, the 3D scene, as defined
on the SDF file above.
diff --git a/tutorials/server_config.md b/tutorials/server_config.md
index 72dd2ba78e..4c94efd113 100644
--- a/tutorials/server_config.md
+++ b/tutorials/server_config.md
@@ -18,7 +18,7 @@ There are a few places where the plugins can be defined:
where `<#>` is Gazebo Sim's major version.
The behavior of Gazebo when loading these plugins depends on the
-``policy set in ``:
+`` policy set in ``:
- `true`: Plugins
in the SDF file are first loaded, followed by plugins from config files
From f6af0c64f39083e92174a3ccbb3a5a6edd39f1d7 Mon Sep 17 00:00:00 2001
From: "Addisu Z. Taddese"
Date: Wed, 28 Aug 2024 01:13:17 -0500
Subject: [PATCH 09/15] Simplify GUI config_action options
Signed-off-by: Addisu Z. Taddese
---
src/gui/Gui.cc | 73 +++++++++++++----------------------------
tutorials/gui_config.md | 19 +++--------
2 files changed, 26 insertions(+), 66 deletions(-)
diff --git a/src/gui/Gui.cc b/src/gui/Gui.cc
index a3d4c354e2..110a34904f 100644
--- a/src/gui/Gui.cc
+++ b/src/gui/Gui.cc
@@ -30,6 +30,7 @@
#include
#include
#include
+#include
#include
#include "gz/sim/Constants.hh"
@@ -89,8 +90,7 @@ auto combineUserAndDefaultPlugins(
auto combinedPlugins = std::make_unique();
_defaultPlugins.DeepCopy(combinedPlugins.get());
- tinyxml2::XMLDocument prependList;
- tinyxml2::XMLDocument appendList;
+ std::set processedUserPlugins;
for (auto pluginElem = _userPlugins->FirstChildElement("plugin");
pluginElem != nullptr;
pluginElem = pluginElem->NextSiblingElement("plugin"))
@@ -110,71 +110,42 @@ auto combineUserAndDefaultPlugins(
configAction = config_action::kGuiDefaultAction;
}
- gzdbg << "Plugin: " << pluginFilename << " act: " << configAction << "\n";
+ if (configAction != config_action::kAppend && configAction != config_action::kAppendReplace)
+ {
+ gzerr << "Unknown config action: " << configAction << ". Using "
+ << config_action::kGuiDefaultAction << " instead." << std::endl;
+ configAction = config_action::kGuiDefaultAction;
+ }
- if (configAction == config_action::kPrependReplace ||
- configAction == config_action::kAppendReplace)
+ bool replacedPlugin{false};
+ if (configAction == config_action::kAppendReplace)
{
- // Remove all matching plugins
for (auto elem = combinedPlugins->FirstChildElement("plugin");
- elem != nullptr;)
+ elem != nullptr && processedUserPlugins.count(elem) == 0;
+ elem = elem->NextSiblingElement("plugin"))
{
if (elem->Attribute("filename", pluginFilename))
{
- gzdbg << "\t Removing " << pluginFilename << "\n";
auto tmp = elem;
- elem = elem->NextSiblingElement("plugin");
+ // Insert the replacement
+ auto clonedPlugin = pluginElem->DeepClone(combinedPlugins.get());
+ elem = combinedPlugins->InsertAfterChild(elem, clonedPlugin)->ToElement();
+ // Remove the original
combinedPlugins->DeleteNode(tmp);
- }
- else
- {
- elem = elem->NextSiblingElement("plugin");
+ replacedPlugin = true;
}
}
}
- if (configAction == config_action::kPrependReplace ||
- configAction == config_action::kPrepend)
- {
- auto clonedPlugin = pluginElem->DeepClone(&prependList);
- prependList.InsertEndChild(clonedPlugin);
- }
- else if (configAction == config_action::kAppendReplace ||
- configAction == config_action::kAppend)
- {
- auto clonedPlugin = pluginElem->DeepClone(&appendList);
- appendList.InsertEndChild(clonedPlugin);
- }
- else
- {
- gzerr << "Unknown config action: " << configAction << std::endl;
- }
- }
- // At this point, combinedPlugins has been cleared of duplicate plugins
- // and prependList and appendList contain the list of plugins to be
- // prepended and appended respectively in the correct order.
- tinyxml2::XMLNode *lastInsertedNode = nullptr;
- for (auto pluginElem = prependList.FirstChildElement();
- pluginElem != nullptr; pluginElem = pluginElem->NextSiblingElement())
- {
- auto clonedPlugin = pluginElem->DeepClone(combinedPlugins.get());
- if (lastInsertedNode == nullptr)
- {
- lastInsertedNode = combinedPlugins->InsertFirstChild(clonedPlugin);
- }
- else
+ if (configAction == config_action::kAppend ||
+ (configAction == config_action::kAppendReplace && !replacedPlugin))
{
- combinedPlugins->InsertAfterChild(lastInsertedNode, clonedPlugin);
+ auto clonedPlugin = pluginElem->DeepClone(combinedPlugins.get());
+ auto insertedElem = combinedPlugins->InsertEndChild(clonedPlugin);
+ processedUserPlugins.insert(insertedElem );
}
}
- for (auto pluginElem = appendList.FirstChildElement();
- pluginElem != nullptr; pluginElem = pluginElem->NextSiblingElement())
- {
- auto clonedPlugin = pluginElem->DeepClone(combinedPlugins.get());
- combinedPlugins->InsertEndChild(clonedPlugin);
- }
-
return combinedPlugins;
}
return _userPlugins;
diff --git a/tutorials/gui_config.md b/tutorials/gui_config.md
index 310960d3b0..68434b1cb6 100644
--- a/tutorials/gui_config.md
+++ b/tutorials/gui_config.md
@@ -30,27 +30,16 @@ How Gazebo combines these plugins is determined by the
both places, by default, only the one specified in the SDF file will be
loaded. However, plugins in the SDF file can specify how they should be loaded
by setting `` tag inside each ``.
- Four options are available:
+ Two options are available:
- `append_replace` (default): The plugin from the SDF file is appended to the
list of plugins to be loaded. Any plugin from the default configuration file
- with the same file name will be removed.
+ with the same file name will be replaced. If replacement occurs, the replacement
+ plugin will take the position of the replaced plugin in the order of plugins.
+ If replacement does not occur, this behaves as `append`.
- `append`: The plugin from the SDF file is appended to the list of plugins
to be loaded. Any plugin from the default configuration file with the same
file name will also be loaded. This is useful for some plugins where it makes sense
to have two or more of (e.g. `ImageDispay`).
- - `prepend_replace`: The plugin from the SDF file is prepended to the
- list of plugins to be loaded. Any plugin from the default configuration file
- with the same file name will be removed. A typical use of this option is
- when overriding the settings of `MinimalScene` plugin since it
- needs to appear first in the list of plugins for the 3D scene to occupy the large
- pane on the left side of the GUI.
- - `append`: The plugin from the SDF file is prepended to the list of plugins
- to be loaded. Any plugin from the default configuration file with the same
- file name will also be loaded.
-
- The four options can be classified into two categories based on whether
- they append or prepend to the list. Within each category, the plugins
- will keep the order in which they are specified in the SDF file.
The main use case for this policy is for users to rely on
the default list of plugins and only add extra plugins they need for the
From 19148a80ed1eda3294aa46fd8daeac07c468f1f9 Mon Sep 17 00:00:00 2001
From: "Addisu Z. Taddese"
Date: Wed, 28 Aug 2024 16:53:10 -0500
Subject: [PATCH 10/15] More updates to GUI tutorial, fix includeDefaultPlugins
logic
Signed-off-by: Addisu Z. Taddese
---
src/SimulationRunner.cc | 28 +++++-------
src/gui/Gui.cc | 8 ++--
tutorials/gui_config.md | 99 ++++++++++++++++++++++++++++++++++-------
3 files changed, 101 insertions(+), 34 deletions(-)
diff --git a/src/SimulationRunner.cc b/src/SimulationRunner.cc
index aceb05360d..c95048cca0 100644
--- a/src/SimulationRunner.cc
+++ b/src/SimulationRunner.cc
@@ -266,6 +266,18 @@ SimulationRunner::SimulationRunner(const sdf::World &_world,
if (_world.Gui())
{
this->guiMsg = convert(*_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"};
@@ -1645,20 +1657,4 @@ void SimulationRunner::CreateEntities(const sdf::World &_world)
// 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())
- {
- 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(""));
- }
- }
- }
}
diff --git a/src/gui/Gui.cc b/src/gui/Gui.cc
index 110a34904f..b33c0e9401 100644
--- a/src/gui/Gui.cc
+++ b/src/gui/Gui.cc
@@ -85,7 +85,7 @@ auto combineUserAndDefaultPlugins(
std::unique_ptr _userPlugins,
const tinyxml2::XMLDocument &_defaultPlugins, bool _includeDefaultPlugins)
{
- if (!_includeDefaultPlugins)
+ if (_includeDefaultPlugins)
{
auto combinedPlugins = std::make_unique();
_defaultPlugins.DeepCopy(combinedPlugins.get());
@@ -110,7 +110,8 @@ auto combineUserAndDefaultPlugins(
configAction = config_action::kGuiDefaultAction;
}
- if (configAction != config_action::kAppend && configAction != config_action::kAppendReplace)
+ if (configAction != config_action::kAppend &&
+ configAction != config_action::kAppendReplace)
{
gzerr << "Unknown config action: " << configAction << ". Using "
<< config_action::kGuiDefaultAction << " instead." << std::endl;
@@ -129,7 +130,8 @@ auto combineUserAndDefaultPlugins(
auto tmp = elem;
// Insert the replacement
auto clonedPlugin = pluginElem->DeepClone(combinedPlugins.get());
- elem = combinedPlugins->InsertAfterChild(elem, clonedPlugin)->ToElement();
+ elem = combinedPlugins->InsertAfterChild(elem, clonedPlugin)
+ ->ToElement();
// Remove the original
combinedPlugins->DeleteNode(tmp);
replacedPlugin = true;
diff --git a/tutorials/gui_config.md b/tutorials/gui_config.md
index 68434b1cb6..1d539bac0e 100644
--- a/tutorials/gui_config.md
+++ b/tutorials/gui_config.md
@@ -23,6 +23,11 @@ plugins in the `` element and the default configuration file.
How Gazebo combines these plugins is determined by the
`` policy set in ``:
+- `false` (default): If
+ there are any plugins specified in the SDF file, plugins from the default
+ configuration file are ignored. This allows the user to have complete
+ control over which plugins are loaded.
+
- `true`: Plugins
from the default configuration file merged with plugins from the SDF file.
Plugins from SDF files take precedence over plugins from
@@ -30,6 +35,7 @@ How Gazebo combines these plugins is determined by the
both places, by default, only the one specified in the SDF file will be
loaded. However, plugins in the SDF file can specify how they should be loaded
by setting `` tag inside each ``.
+
Two options are available:
- `append_replace` (default): The plugin from the SDF file is appended to the
list of plugins to be loaded. Any plugin from the default configuration file
@@ -41,19 +47,17 @@ How Gazebo combines these plugins is determined by the
file name will also be loaded. This is useful for some plugins where it makes sense
to have two or more of (e.g. `ImageDispay`).
+ \warning `append` will have unexpected behavior if you save
+ the GUI configuration from Gazebo and rerun the same SDF file. This is because
+ the combined plugin list will be saved in as the default configuration file
+ and when you rerun the SDF file, plugins with `append` will be added in addition
+ to the ones already in the configuration file.
+
The main use case for this policy is for users to rely on
the default list of plugins and only add extra plugins they need for the
application. This policy is also useful for overriding the parameters of a small
subset of the default plugins.
- This is the default setting of this policy in Gazebo Ionic and later.
-
-- `false`: If
- there are any plugins specified in the SDF file, plugins from the default
- configuration file are ignored. This allows the user to have complete
- control over which plugins are loaded. This is the default setting in
- Gazebo Harmonic and earlier.
-
> \* For log-playback, the default file is
> `$HOME/.gz/sim/<#>/playback_gui.config`
@@ -61,10 +65,9 @@ How Gazebo combines these plugins is determined by the
### Default configuration
-Let's try this in practice. First, let's open Gazebo without passing
-any arguments:
+Let's try this in practice. First, let's open the default Gazebo world:
-`gz sim`
+`gz sim default.sdf`
You should see an empty world with several plugins loaded by default, such as the
3D Scene, the play/pause button, etc.
@@ -108,7 +111,7 @@ will be created with default values:
Let's try overriding the default configuration from an SDF file. Open your
favorite editor and save this file as `fuel_preview.sdf`:
-```
+```xml
@@ -170,9 +173,7 @@ Now let's load this world:
`gz sim /fuel_preview.sdf`
-With the default policy,
-
-Notice how the application has only one GUI plugin loaded, the 3D scene, as defined
+Notice how the application has only 3 GUI plugins loaded, as defined
on the SDF file above.
@image html files/gui_config/fuel_preview.png
@@ -182,6 +183,74 @@ the same model loaded into the default GUI layout.
@image html files/gui_config/fuel_preview_no_gui.png
+Now, let's change the policy so that default plugins are included
+
+```xml
+
+
+
+
+
+
+
+ true
+
+
+
+
+
+
+ 3D View
+ false
+ docked
+
+
+ ogre2
+ scene
+ 1.0 1.0 1.0
+ 0.4 0.6 1.0
+ 8.3 7 7.8 0 0.5 -2.4
+
+
+
+ false
+ 5
+ 5
+ floating
+ false
+
+
+
+
+ false
+ 5
+ 5
+ floating
+ false
+
+
+
+
+
+
+ https://fuel.gazebosim.org/1.0/OpenRobotics/models/Sun
+
+
+
+ https://fuel.gazebosim.org/1.0/OpenRobotics/models/Gazebo
+
+
+
+
+```
+
+You will now see the same model loaded in the default GUI layout
+similar to when you deleted the `` element altogether.
+
+@image html files/gui_config/fuel_preview_no_gui.png
+
### Command line
It's often inconvenient to embed your GUI layout directly into every SDF file.
From 1f3fb8f2446ab3113809bfe861959713a45b50fb Mon Sep 17 00:00:00 2001
From: "Addisu Z. Taddese"
Date: Wed, 28 Aug 2024 16:56:38 -0500
Subject: [PATCH 11/15] Remove prepend constants
Signed-off-by: Addisu Z. Taddese
---
include/gz/sim/Constants.hh | 2 --
1 file changed, 2 deletions(-)
diff --git a/include/gz/sim/Constants.hh b/include/gz/sim/Constants.hh
index 21f228a2fc..a276738c95 100644
--- a/include/gz/sim/Constants.hh
+++ b/include/gz/sim/Constants.hh
@@ -28,8 +28,6 @@ inline namespace GZ_SIM_VERSION_NAMESPACE
{
namespace config_action {
constexpr std::string_view kPluginAttribute{"gz:config_action"};
- constexpr std::string_view kPrependReplace{"prepend_replace"};
- constexpr std::string_view kPrepend{"prepend"};
constexpr std::string_view kAppendReplace{"append_replace"};
constexpr std::string_view kAppend{"append"};
constexpr std::string_view kGuiDefaultAction{kAppendReplace};
From c03503376d7a74b4b3a0bbbb5a53332ea6f71c73 Mon Sep 17 00:00:00 2001
From: "Addisu Z. Taddese"
Date: Wed, 28 Aug 2024 17:28:15 -0500
Subject: [PATCH 12/15] Further simplification
Signed-off-by: Addisu Z. Taddese
---
examples/worlds/camera_sensor.sdf | 2 --
include/gz/sim/Constants.hh | 7 ----
src/gui/Gui.cc | 54 ++++++++-----------------------
tutorials/gui_config.md | 41 +++++++++--------------
4 files changed, 30 insertions(+), 74 deletions(-)
diff --git a/examples/worlds/camera_sensor.sdf b/examples/worlds/camera_sensor.sdf
index 7d551db60e..fe68af9f36 100644
--- a/examples/worlds/camera_sensor.sdf
+++ b/examples/worlds/camera_sensor.sdf
@@ -26,7 +26,6 @@
- prepend_replace
3D View
false
@@ -40,7 +39,6 @@
- append
docked
diff --git a/include/gz/sim/Constants.hh b/include/gz/sim/Constants.hh
index a276738c95..96d281ccc7 100644
--- a/include/gz/sim/Constants.hh
+++ b/include/gz/sim/Constants.hh
@@ -26,13 +26,6 @@ namespace gz::sim
// Inline bracket to help doxygen filtering.
inline namespace GZ_SIM_VERSION_NAMESPACE
{
- namespace config_action {
- constexpr std::string_view kPluginAttribute{"gz:config_action"};
- constexpr std::string_view kAppendReplace{"append_replace"};
- constexpr std::string_view kAppend{"append"};
- constexpr std::string_view kGuiDefaultAction{kAppendReplace};
- }
-
constexpr std::string_view kPoliciesTag{"gz:policies"};
}
} // namespace gz::sim
diff --git a/src/gui/Gui.cc b/src/gui/Gui.cc
index b33c0e9401..2d6f4549f1 100644
--- a/src/gui/Gui.cc
+++ b/src/gui/Gui.cc
@@ -96,51 +96,25 @@ auto combineUserAndDefaultPlugins(
pluginElem = pluginElem->NextSiblingElement("plugin"))
{
const char *pluginFilename = pluginElem->Attribute("filename");
- std::string configAction = "";
-
- auto configActionElement =
- pluginElem->FirstChildElement(config_action::kPluginAttribute.data());
- if (configActionElement)
- {
- configAction = configActionElement->GetText();
- }
-
- if (configAction == "")
- {
- configAction = config_action::kGuiDefaultAction;
- }
-
- if (configAction != config_action::kAppend &&
- configAction != config_action::kAppendReplace)
- {
- gzerr << "Unknown config action: " << configAction << ". Using "
- << config_action::kGuiDefaultAction << " instead." << std::endl;
- configAction = config_action::kGuiDefaultAction;
- }
bool replacedPlugin{false};
- if (configAction == config_action::kAppendReplace)
+ for (auto elem = combinedPlugins->FirstChildElement("plugin");
+ elem != nullptr && processedUserPlugins.count(elem) == 0;
+ elem = elem->NextSiblingElement("plugin"))
{
- for (auto elem = combinedPlugins->FirstChildElement("plugin");
- elem != nullptr && processedUserPlugins.count(elem) == 0;
- elem = elem->NextSiblingElement("plugin"))
+ if (elem->Attribute("filename", pluginFilename))
{
- if (elem->Attribute("filename", pluginFilename))
- {
- auto tmp = elem;
- // Insert the replacement
- auto clonedPlugin = pluginElem->DeepClone(combinedPlugins.get());
- elem = combinedPlugins->InsertAfterChild(elem, clonedPlugin)
- ->ToElement();
- // Remove the original
- combinedPlugins->DeleteNode(tmp);
- replacedPlugin = true;
- }
+ auto tmp = elem;
+ // Insert the replacement
+ auto clonedPlugin = pluginElem->DeepClone(combinedPlugins.get());
+ elem = combinedPlugins->InsertAfterChild(elem, clonedPlugin)
+ ->ToElement();
+ // Remove the original
+ combinedPlugins->DeleteNode(tmp);
+ replacedPlugin = true;
}
}
-
- if (configAction == config_action::kAppend ||
- (configAction == config_action::kAppendReplace && !replacedPlugin))
+ if (!replacedPlugin)
{
auto clonedPlugin = pluginElem->DeepClone(combinedPlugins.get());
auto insertedElem = combinedPlugins->InsertEndChild(clonedPlugin);
@@ -157,7 +131,7 @@ auto combineUserAndDefaultPlugins(
struct GuiPolicies
{
/// \brief Whether to include default plugins
- bool includeGuiDefaultPlugins{false};
+ bool includeGuiDefaultPlugins{true};
/// \brief Parse policies from a GUI message
/// \param[in] _msg Input message
diff --git a/tutorials/gui_config.md b/tutorials/gui_config.md
index 1d539bac0e..f178e5e0e7 100644
--- a/tutorials/gui_config.md
+++ b/tutorials/gui_config.md
@@ -23,40 +23,26 @@ plugins in the `` element and the default configuration file.
How Gazebo combines these plugins is determined by the
`` policy set in ``:
-- `false` (default): If
- there are any plugins specified in the SDF file, plugins from the default
- configuration file are ignored. This allows the user to have complete
- control over which plugins are loaded.
-
- `true`: Plugins
from the default configuration file merged with plugins from the SDF file.
Plugins from SDF files take precedence over plugins from
the default configuration file. This means, if a plugin is specified in
both places, by default, only the one specified in the SDF file will be
- loaded. However, plugins in the SDF file can specify how they should be loaded
- by setting `` tag inside each ``.
-
- Two options are available:
- - `append_replace` (default): The plugin from the SDF file is appended to the
- list of plugins to be loaded. Any plugin from the default configuration file
- with the same file name will be replaced. If replacement occurs, the replacement
+ loaded. If replacement occurs, the replacement
plugin will take the position of the replaced plugin in the order of plugins.
- If replacement does not occur, this behaves as `append`.
- - `append`: The plugin from the SDF file is appended to the list of plugins
- to be loaded. Any plugin from the default configuration file with the same
- file name will also be loaded. This is useful for some plugins where it makes sense
- to have two or more of (e.g. `ImageDispay`).
-
- \warning `append` will have unexpected behavior if you save
- the GUI configuration from Gazebo and rerun the same SDF file. This is because
- the combined plugin list will be saved in as the default configuration file
- and when you rerun the SDF file, plugins with `append` will be added in addition
- to the ones already in the configuration file.
+ If replacement does not occur, the plugin is appended to the end of the list.
The main use case for this policy is for users to rely on
the default list of plugins and only add extra plugins they need for the
application. This policy is also useful for overriding the parameters of a small
- subset of the default plugins.
+ subset of the default plugins.This is the default setting in
+ Gazebo Ionic and later.
+
+- `false`: If
+ there are any plugins specified in the SDF file, plugins from the default
+ configuration file are ignored. This allows the user to have complete
+ control over which plugins are loaded. This is the default setting in
+ Gazebo Harmonic and earlier.
> \* For log-playback, the default file is
> `$HOME/.gz/sim/<#>/playback_gui.config`
@@ -120,6 +106,10 @@ favorite editor and save this file as `fuel_preview.sdf`:
name="gz::sim::systems::SceneBroadcaster">
+
+ false
+
+
@@ -247,7 +237,8 @@ Now, let's change the policy so that default plugins are included
```
You will now see the same model loaded in the default GUI layout
-similar to when you deleted the `` element altogether.
+similar to when you deleted the `` element altogether. Note that this will also
+be the behavior if we removed `` tag.
@image html files/gui_config/fuel_preview_no_gui.png
From 303e18ba127b39c75d6c9873d26a7d06f266e7f6 Mon Sep 17 00:00:00 2001
From: "Addisu Z. Taddese"
Date: Wed, 28 Aug 2024 20:07:52 -0500
Subject: [PATCH 13/15] Fix tests and address reviewer feedback
Signed-off-by: Addisu Z. Taddese
---
examples/worlds/camera_sensor.sdf | 2 +-
src/ServerConfig.cc | 4 ++--
src/Server_TEST.cc | 6 ++----
src/SimulationRunner.cc | 2 +-
test/integration/reset_sensors.cc | 2 ++
test/worlds/air_pressure.sdf | 3 +++
test/worlds/air_speed.sdf | 3 +++
test/worlds/reset_sensors.sdf | 3 +++
tutorials/gui_config.md | 4 ++--
tutorials/server_config.md | 2 +-
10 files changed, 20 insertions(+), 11 deletions(-)
diff --git a/examples/worlds/camera_sensor.sdf b/examples/worlds/camera_sensor.sdf
index fe68af9f36..0cee711b47 100644
--- a/examples/worlds/camera_sensor.sdf
+++ b/examples/worlds/camera_sensor.sdf
@@ -21,7 +21,7 @@
- true
+ true
diff --git a/src/ServerConfig.cc b/src/ServerConfig.cc
index b800c541aa..4e75a68ea0 100644
--- a/src/ServerConfig.cc
+++ b/src/ServerConfig.cc
@@ -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;
@@ -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;
diff --git a/src/Server_TEST.cc b/src/Server_TEST.cc
index f2248cb121..5f7697eeab 100644
--- a/src/Server_TEST.cc
+++ b/src/Server_TEST.cc
@@ -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");
@@ -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));
diff --git a/src/SimulationRunner.cc b/src/SimulationRunner.cc
index c95048cca0..268e956cda 100644
--- a/src/SimulationRunner.cc
+++ b/src/SimulationRunner.cc
@@ -1644,7 +1644,7 @@ void SimulationRunner::CreateEntities(const sdf::World &_world)
// plugins.
defaultPlugins.remove_if(isPluginLoaded);
- gzdbg << "Also loading the following default jplugins:\n";
+ gzdbg << "Additional plugins to load:\n";
for (const auto &plugin : defaultPlugins)
{
gzdbg << plugin.Plugin().Name() << " " << plugin.Plugin().Filename()
diff --git a/test/integration/reset_sensors.cc b/test/integration/reset_sensors.cc
index 7b9c43d492..be9c3b6a38 100644
--- a/test/integration/reset_sensors.cc
+++ b/test/integration/reset_sensors.cc
@@ -23,6 +23,7 @@
#include
#include
+#include
#include
#include
@@ -336,6 +337,7 @@ TEST_F(ResetFixture, GZ_UTILS_TEST_DISABLED_ON_MAC(HandleReset))
imageReceiver.msgReceived = false;
server.Run(true, 2000 - server.IterationCount().value(), false);
+ std::this_thread::sleep_for(20ms);
// Check iterator state
EXPECT_EQ(2000u, server.IterationCount().value());
diff --git a/test/worlds/air_pressure.sdf b/test/worlds/air_pressure.sdf
index 0679f9e280..d66cb0fccd 100644
--- a/test/worlds/air_pressure.sdf
+++ b/test/worlds/air_pressure.sdf
@@ -5,6 +5,9 @@
0
+
+ false
+
diff --git a/test/worlds/air_speed.sdf b/test/worlds/air_speed.sdf
index feb3347655..b23d7ee6d5 100644
--- a/test/worlds/air_speed.sdf
+++ b/test/worlds/air_speed.sdf
@@ -5,6 +5,9 @@
0
+
+ false
+
diff --git a/test/worlds/reset_sensors.sdf b/test/worlds/reset_sensors.sdf
index 733658fefc..7f8db14a7e 100644
--- a/test/worlds/reset_sensors.sdf
+++ b/test/worlds/reset_sensors.sdf
@@ -1,6 +1,9 @@
+
+ false
+
diff --git a/tutorials/gui_config.md b/tutorials/gui_config.md
index f178e5e0e7..0304f1131a 100644
--- a/tutorials/gui_config.md
+++ b/tutorials/gui_config.md
@@ -35,7 +35,7 @@ How Gazebo combines these plugins is determined by the
The main use case for this policy is for users to rely on
the default list of plugins and only add extra plugins they need for the
application. This policy is also useful for overriding the parameters of a small
- subset of the default plugins.This is the default setting in
+ subset of the default plugins. This is the default setting in
Gazebo Ionic and later.
- `false`: If
@@ -79,7 +79,7 @@ Let's try customizing it:
3. Reload Gazebo:
- `gz sim`
+ `gz sim default.sdf`
Note how the UI is now in dark mode!
diff --git a/tutorials/server_config.md b/tutorials/server_config.md
index 4c94efd113..650eafe0c4 100644
--- a/tutorials/server_config.md
+++ b/tutorials/server_config.md
@@ -179,7 +179,7 @@ Now, let's modify the SDF file to change the policy `
false
-
+
Date: Thu, 29 Aug 2024 03:32:46 +0000
Subject: [PATCH 14/15] fix test
Signed-off-by: Ian Chen
---
src/Server_TEST.cc | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/src/Server_TEST.cc b/src/Server_TEST.cc
index 5f7697eeab..e9982d1c9c 100644
--- a/src/Server_TEST.cc
+++ b/src/Server_TEST.cc
@@ -511,7 +511,7 @@ TEST_P(ServerFixture, SdfStringServerConfig)
EXPECT_TRUE(*server.Paused());
EXPECT_EQ(0u, *server.IterationCount());
EXPECT_EQ(3u, *server.EntityCount());
- EXPECT_EQ(2u, *server.SystemCount());
+ EXPECT_EQ(5u, *server.SystemCount());
}
/////////////////////////////////////////////////
From ad0465bfd6df77cc647512d891ff31bee747a2ca Mon Sep 17 00:00:00 2001
From: "Addisu Z. Taddese"
Date: Wed, 28 Aug 2024 23:35:15 -0500
Subject: [PATCH 15/15] Set include_server_config_plugins for
`TestWorldSansPhysics`
Signed-off-by: Addisu Z. Taddese
---
src/Server_TEST.cc | 2 +-
test/test_config.hh.in | 3 +++
2 files changed, 4 insertions(+), 1 deletion(-)
diff --git a/src/Server_TEST.cc b/src/Server_TEST.cc
index e9982d1c9c..5f7697eeab 100644
--- a/src/Server_TEST.cc
+++ b/src/Server_TEST.cc
@@ -511,7 +511,7 @@ TEST_P(ServerFixture, SdfStringServerConfig)
EXPECT_TRUE(*server.Paused());
EXPECT_EQ(0u, *server.IterationCount());
EXPECT_EQ(3u, *server.EntityCount());
- EXPECT_EQ(5u, *server.SystemCount());
+ EXPECT_EQ(2u, *server.SystemCount());
}
/////////////////////////////////////////////////
diff --git a/test/test_config.hh.in b/test/test_config.hh.in
index b367ed89de..89118966c9 100644
--- a/test/test_config.hh.in
+++ b/test/test_config.hh.in
@@ -48,6 +48,9 @@ struct TestWorldSansPhysics
static std::string world = std::string(""
""
""
+ ""
+ " false"
+ ""
""