Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Break out server constructor #2638

Open
wants to merge 4 commits into
base: gz-sim8
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
122 changes: 2 additions & 120 deletions src/Server.cc
Original file line number Diff line number Diff line change
Expand Up @@ -33,31 +33,12 @@
#include "gz/sim/Server.hh"
#include "gz/sim/Util.hh"

#include "MeshInertiaCalculator.hh"
#include "ServerPrivate.hh"
#include "SimulationRunner.hh"

using namespace gz;
using namespace sim;

/// \brief This struct provides access to the default world.
struct DefaultWorld
{
/// \brief Get the default world as a string.
/// Plugins will be loaded from the server.config file.
/// \return An SDF string that contains the default world.
public: static std::string &World()
{
static std::string world = std::string("<?xml version='1.0'?>"
"<sdf version='1.6'>"
"<world name='default'>") +
"</world>"
"</sdf>";

return world;
}
};

/////////////////////////////////////////////////
Server::Server(const ServerConfig &_config)
: dataPtr(new ServerPrivate)
Expand Down Expand Up @@ -96,107 +77,8 @@ Server::Server(const ServerConfig &_config)

addResourcePaths();

sdf::Errors errors;

switch (_config.Source())
{
// Load a world if specified. Check SDF string first, then SDF file
case ServerConfig::SourceType::kSdfRoot:
{
this->dataPtr->sdfRoot = _config.SdfRoot()->Clone();
gzmsg << "Loading SDF world from SDF DOM.\n";
break;
}

case ServerConfig::SourceType::kSdfString:
{
std::string msg = "Loading SDF string. ";
if (_config.SdfFile().empty())
{
msg += "File path not available.\n";
}
else
{
msg += "File path [" + _config.SdfFile() + "].\n";
}
gzmsg << msg;
sdf::ParserConfig sdfParserConfig = sdf::ParserConfig::GlobalConfig();
sdfParserConfig.SetStoreResolvedURIs(true);
sdfParserConfig.SetCalculateInertialConfiguration(
sdf::ConfigureResolveAutoInertials::SKIP_CALCULATION_IN_LOAD);
errors = this->dataPtr->sdfRoot.LoadSdfString(
_config.SdfString(), sdfParserConfig);
this->dataPtr->sdfRoot.ResolveAutoInertials(errors, sdfParserConfig);
break;
}

case ServerConfig::SourceType::kSdfFile:
{
std::string filePath = resolveSdfWorldFile(_config.SdfFile(),
_config.ResourceCache());

if (filePath.empty())
{
gzerr << "Failed to find world [" << _config.SdfFile() << "]"
<< std::endl;
return;
}

gzmsg << "Loading SDF world file[" << filePath << "].\n";

sdf::Root sdfRoot;
sdf::ParserConfig sdfParserConfig = sdf::ParserConfig::GlobalConfig();
sdfParserConfig.SetStoreResolvedURIs(true);
sdfParserConfig.SetCalculateInertialConfiguration(
sdf::ConfigureResolveAutoInertials::SKIP_CALCULATION_IN_LOAD);

MeshInertiaCalculator meshInertiaCalculator;
sdfParserConfig.RegisterCustomInertiaCalc(meshInertiaCalculator);
// \todo(nkoenig) Async resource download.
// This call can block for a long period of time while
// resources are downloaded. Blocking here causes the GUI to block with
// a black screen (search for "Async resource download" in
// 'src/gui_main.cc'.
errors = sdfRoot.Load(filePath, sdfParserConfig);
if (errors.empty() || _config.BehaviorOnSdfErrors() !=
ServerConfig::SdfErrorBehavior::EXIT_IMMEDIATELY)
{
if (sdfRoot.Model() == nullptr) {
this->dataPtr->sdfRoot = std::move(sdfRoot);
}
else
{
// If the specified file only contains a model, load the default
// world and add the model to it.
errors = this->dataPtr->sdfRoot.LoadSdfString(
DefaultWorld::World(), sdfParserConfig);
sdf::World *world = this->dataPtr->sdfRoot.WorldByIndex(0);
if (world == nullptr) {
return;
}
world->AddModel(*sdfRoot.Model());
if (errors.empty() || _config.BehaviorOnSdfErrors() !=
ServerConfig::SdfErrorBehavior::EXIT_IMMEDIATELY)
{
errors = this->dataPtr->sdfRoot.UpdateGraphs();
}
}
}

this->dataPtr->sdfRoot.ResolveAutoInertials(errors, sdfParserConfig);
break;
}

case ServerConfig::SourceType::kNone:
default:
{
gzmsg << "Loading default world.\n";
// Load an empty world.
/// \todo(nkoenig) Add a "AddWorld" function to sdf::Root.
errors = this->dataPtr->sdfRoot.LoadSdfString(DefaultWorld::World());
break;
}
}
// Loads the SDF root object based on values in a ServerConfig object.
sdf::Errors errors = this->dataPtr->LoadSdfRootHelper(_config);

if (!errors.empty())
{
Expand Down
121 changes: 121 additions & 0 deletions src/ServerPrivate.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,9 @@

#include <tinyxml2.h>

#include <string>
#include <utility>

#include <gz/msgs/boolean.pb.h>
#include <gz/msgs/server_control.pb.h>
#include <gz/msgs/stringmsg.pb.h>
Expand All @@ -32,6 +35,7 @@
#include <gz/fuel_tools/Interface.hh>

#include "gz/sim/Util.hh"
#include "MeshInertiaCalculator.hh"
#include "SimulationRunner.hh"

using namespace gz;
Expand Down Expand Up @@ -574,3 +578,120 @@ std::string ServerPrivate::FetchResourceUri(const common::URI &_uri)
{
return this->FetchResource(_uri.Str());
}

//////////////////////////////////////////////////
sdf::Errors ServerPrivate::LoadSdfRootHelper(const ServerConfig &_config)
{
sdf::Errors errors;

switch (_config.Source())
{
// Load a world if specified. Check SDF string first, then SDF file
case ServerConfig::SourceType::kSdfRoot:
{
this->sdfRoot = _config.SdfRoot()->Clone();
gzmsg << "Loading SDF world from SDF DOM.\n";
break;
}

case ServerConfig::SourceType::kSdfString:
{
std::string msg = "Loading SDF string. ";
if (_config.SdfFile().empty())
{
msg += "File path not available.\n";
}
else
{
msg += "File path [" + _config.SdfFile() + "].\n";
}
gzmsg << msg;
sdf::ParserConfig sdfParserConfig = sdf::ParserConfig::GlobalConfig();
sdfParserConfig.SetStoreResolvedURIs(true);
sdfParserConfig.SetCalculateInertialConfiguration(
sdf::ConfigureResolveAutoInertials::SKIP_CALCULATION_IN_LOAD);
errors = this->sdfRoot.LoadSdfString(
_config.SdfString(), sdfParserConfig);
this->sdfRoot.ResolveAutoInertials(errors, sdfParserConfig);
break;
}

case ServerConfig::SourceType::kSdfFile:
{
std::string filePath = resolveSdfWorldFile(_config.SdfFile(),
mjcarroll marked this conversation as resolved.
Show resolved Hide resolved
_config.ResourceCache());

if (filePath.empty())
{
std::string errStr = "Failed to find world ["
+ _config.SdfFile() + "]";
gzerr << errStr << std::endl;
errors.push_back({sdf::ErrorCode::FILE_READ, errStr});
return errors;
}

gzmsg << "Loading SDF world file[" << filePath << "].\n";

sdf::Root sdfRootLocal;
sdf::ParserConfig sdfParserConfig = sdf::ParserConfig::GlobalConfig();
sdfParserConfig.SetStoreResolvedURIs(true);
sdfParserConfig.SetCalculateInertialConfiguration(
sdf::ConfigureResolveAutoInertials::SKIP_CALCULATION_IN_LOAD);

MeshInertiaCalculator meshInertiaCalculator;
sdfParserConfig.RegisterCustomInertiaCalc(meshInertiaCalculator);
// \todo(nkoenig) Async resource download.
// This call can block for a long period of time while
// resources are downloaded. Blocking here causes the GUI to block with
// a black screen (search for "Async resource download" in
// 'src/gui_main.cc'.
errors = sdfRootLocal.Load(filePath, sdfParserConfig);
if (errors.empty() || _config.BehaviorOnSdfErrors() !=
ServerConfig::SdfErrorBehavior::EXIT_IMMEDIATELY)
{
if (sdfRootLocal.Model() == nullptr) {
this->sdfRoot = std::move(sdfRootLocal);
mjcarroll marked this conversation as resolved.
Show resolved Hide resolved
}
else
{
sdf::World defaultWorld;
defaultWorld.SetName("default");

// If the specified file only contains a model, load the default
// world and add the model to it.
errors = this->sdfRoot.AddWorld(defaultWorld);
sdf::World *world = this->sdfRoot.WorldByIndex(0);
if (world == nullptr) {
errors.push_back({sdf::ErrorCode::FATAL_ERROR,
"sdf::World pointer is null"});
return errors;
}
world->AddModel(*sdfRootLocal.Model());
if (errors.empty() || _config.BehaviorOnSdfErrors() !=
ServerConfig::SdfErrorBehavior::EXIT_IMMEDIATELY)
{
errors = this->sdfRoot.UpdateGraphs();
}
}
}

this->sdfRoot.ResolveAutoInertials(errors, sdfParserConfig);
break;
}

case ServerConfig::SourceType::kNone:
default:
{
gzmsg << "Loading default world.\n";

sdf::World defaultWorld;
defaultWorld.SetName("default");

// Load an empty world.
errors = this->sdfRoot.AddWorld(defaultWorld);
break;
}
}

return errors;
}
6 changes: 6 additions & 0 deletions src/ServerPrivate.hh
Original file line number Diff line number Diff line change
Expand Up @@ -99,6 +99,12 @@ namespace gz
/// \return Path to the downloaded resource, empty on error.
public: std::string FetchResourceUri(const common::URI &_uri);

/// \brief Helper function that loads an SDF root object based on
/// values in a ServerConfig object.
/// \param[in] _config Server config to read from.
/// \return Set of SDF errors.
public: sdf::Errors LoadSdfRootHelper(const ServerConfig &_config);

/// \brief Signal handler callback
/// \param[in] _sig The signal number
private: void OnSignal(int _sig);
Expand Down
Loading