Skip to content

ServerConfig accepts an sdf::Root DOM object #1333

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

Merged
merged 18 commits into from
Apr 1, 2022
Merged
Show file tree
Hide file tree
Changes from 3 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
12 changes: 12 additions & 0 deletions include/ignition/gazebo/ServerConfig.hh
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include <string>
#include <vector>
#include <sdf/Element.hh>
#include <sdf/Root.hh>
#include <ignition/gazebo/config.hh>
#include <ignition/gazebo/Export.hh>

Expand Down Expand Up @@ -175,6 +176,17 @@ namespace ignition
/// \return The full contents of the SDF string, or empty string.
public: std::string SdfString() const;

/// \brief Set the SDF Root DOM object. The sdf::Root object will take
/// precendence over ServerConfig::SdfString() and
/// ServerConfig::SdfFile().
/// \param[in] _root SDF Root object to use.
public: void SetSdfRoot(const sdf::Root &_root) const;

/// \brief Get the SDF Root DOM object.
/// \return SDF Root object to use, or std::nullopt if the sdf::Root
/// has not been set via ServerConfig::SetSdfRoot().
public: const std::optional<sdf::Root> &SdfRoot() const;

/// \brief Set the update rate in Hertz. Value <=0 are ignored.
/// \param[in] _hz The desired update rate of the server in Hertz.
public: void SetUpdateRate(const double &_hz);
Expand Down
18 changes: 18 additions & 0 deletions include/ignition/gazebo/Util.hh
Original file line number Diff line number Diff line change
Expand Up @@ -210,6 +210,24 @@ namespace ignition
const EntityComponentManager &_ecm,
bool _excludeWorld = true);

/// \brief Convert an SDF world filename string, such as "shapes.sdf", to
/// full system file path.
/// The provided SDF filename may be a Fuel URI, relative path, name
/// of an installed Gazebo world filename, or an absolute path.
/// \param[in] _sdfFile An SDF world filename such as:
/// 1. "shapes.sdf" - This is referencing an installed world file.
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It could also be a relative path to a file in the current directory.

/// 2. "../shapes.sdf" - This is referencing a relative world file.
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It's worth mentioning what it's relative to. It could be either the running directory or any path in IGN_GAZEBO_RESOURCE_PATH

/// 3. "/home/user/shapes.sdf" - This is reference an absolute world
/// file.
/// 4. "https://fuel.ignitionrobotics.org/1.0/openrobotics/worlds/shapes.sdf" - This is referencing a Fuel URI. This will download the world file.
/// \param[in] _fuelResourceCache Path to a Fuel resource cache, if
/// known.
/// \return Full path to the SDF world file. An empty string is returned
/// if the file could not be found.
std::string IGNITION_GAZEBO_VISIBLE resolveSdfWorldFile(
const std::string &_sdfFilename,
const std::string &_fuelResourceCache = "");

/// \brief Helper function to "enable" a component (i.e. create it if it
/// doesn't exist) or "disable" a component (i.e. remove it if it exists).
/// \param[in] _ecm Mutable reference to the ECM
Expand Down
71 changes: 8 additions & 63 deletions src/Server.cc
Original file line number Diff line number Diff line change
Expand Up @@ -33,31 +33,6 @@
using namespace ignition;
using namespace gazebo;

//////////////////////////////////////////////////
// Getting the first .sdf file in the path
std::string findFuelResourceSdf(const std::string &_path)
{
if (!common::exists(_path))
return "";

for (common::DirIter file(_path); file != common::DirIter(); ++file)
{
std::string current(*file);
if (!common::isFile(current))
continue;

auto fileName = common::basename(current);
auto fileExtensionIndex = fileName.rfind(".");
auto fileExtension = fileName.substr(fileExtensionIndex + 1);

if (fileExtension == "sdf")
{
return current;
}
}
return "";
}

/// \brief This struct provides access to the default world.
struct DefaultWorld
{
Expand Down Expand Up @@ -99,7 +74,12 @@ Server::Server(const ServerConfig &_config)
sdf::Errors errors;

// Load a world if specified. Check SDF string first, then SDF file
if (!_config.SdfString().empty())
if (_config.SdfRoot())
{
this->dataPtr->sdfRoot = _config.SdfRoot()->Clone();
ignmsg << "Loading SDF world from SDF DOM.\n";
}
else if (!_config.SdfString().empty())
{
std::string msg = "Loading SDF string. ";
if (_config.SdfFile().empty())
Expand All @@ -115,43 +95,8 @@ Server::Server(const ServerConfig &_config)
}
else if (!_config.SdfFile().empty())
{
std::string filePath;

// Check Fuel if it's a URL
auto sdfUri = common::URI(_config.SdfFile());
if (sdfUri.Scheme() == "http" || sdfUri.Scheme() == "https")
{
std::string fuelCachePath;
if (this->dataPtr->fuelClient->CachedWorld(common::URI(_config.SdfFile()),
fuelCachePath))
{
filePath = findFuelResourceSdf(fuelCachePath);
}
else if (auto result = this->dataPtr->fuelClient->DownloadWorld(
common::URI(_config.SdfFile()), fuelCachePath))
{
filePath = findFuelResourceSdf(fuelCachePath);
}
else
{
ignwarn << "Fuel couldn't download URL [" << _config.SdfFile()
<< "], error: [" << result.ReadableResult() << "]"
<< std::endl;
}
}

if (filePath.empty())
{
common::SystemPaths systemPaths;

// Worlds from environment variable
systemPaths.SetFilePathEnv(kResourcePathEnv);

// Worlds installed with ign-gazebo
systemPaths.AddFilePaths(IGN_GAZEBO_WORLD_INSTALL_DIR);

filePath = systemPaths.FindFile(_config.SdfFile());
}
std::string filePath = resolveSdfWorldFile(_config.SdfFile(),
_config.ResourceCache());

if (filePath.empty())
{
Expand Down
27 changes: 27 additions & 0 deletions src/ServerConfig.cc
Original file line number Diff line number Diff line change
Expand Up @@ -301,6 +301,9 @@ class ignition::gazebo::ServerConfigPrivate

/// \brief is the headless mode active.
public: bool isHeadlessRendering{false};

/// \brief Optional SDF root object.
public: std::optional<sdf::Root> sdfRoot;
};

//////////////////////////////////////////////////
Expand All @@ -323,6 +326,7 @@ bool ServerConfig::SetSdfFile(const std::string &_file)
{
this->dataPtr->sdfFile = _file;
this->dataPtr->sdfString = "";
this->dataPtr->sdfRoot = std::nullopt;
return true;
}

Expand All @@ -337,6 +341,7 @@ bool ServerConfig::SetSdfString(const std::string &_sdfString)
{
this->dataPtr->sdfFile = "";
this->dataPtr->sdfString = _sdfString;
this->dataPtr->sdfRoot = std::nullopt;
return true;
}

Expand Down Expand Up @@ -697,6 +702,28 @@ const std::vector<std::string> &ServerConfig::LogRecordTopics() const
return this->dataPtr->logRecordTopics;
}

/////////////////////////////////////////////////
void ServerConfig::SetSdfRoot(const sdf::Root &_root) const
{
this->dataPtr->sdfRoot.emplace();

for (uint64_t i = 0; i < _root.WorldCount(); ++i)
{
const sdf::World *world = _root.WorldByIndex(i);
if (world)
this->dataPtr->sdfRoot->AddWorld(*world);
}

this->dataPtr->sdfFile = "";
this->dataPtr->sdfString = "";
}

/////////////////////////////////////////////////
const std::optional<sdf::Root> &ServerConfig::SdfRoot() const
{
return this->dataPtr->sdfRoot;
}

/////////////////////////////////////////////////
void copyElement(sdf::ElementPtr _sdf, const tinyxml2::XMLElement *_xml)
{
Expand Down
24 changes: 24 additions & 0 deletions src/ServerConfig_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -228,3 +228,27 @@ TEST(ServerConfig, GenerateRecordPlugin)
EXPECT_EQ(plugin.Name(), "ignition::gazebo::systems::LogRecord");
}

//////////////////////////////////////////////////
TEST(ServerConfig, SdfRoot)
{
ServerConfig config;
EXPECT_FALSE(config.SdfRoot());
EXPECT_TRUE(config.SdfFile().empty());
EXPECT_TRUE(config.SdfString().empty());

config.SetSdfString("string");
EXPECT_FALSE(config.SdfRoot());
EXPECT_TRUE(config.SdfFile().empty());
EXPECT_FALSE(config.SdfString().empty());

config.SetSdfFile("file");
EXPECT_FALSE(config.SdfRoot());
EXPECT_FALSE(config.SdfFile().empty());
EXPECT_TRUE(config.SdfString().empty());

sdf::Root root;
config.SetSdfRoot(root);
EXPECT_TRUE(config.SdfRoot());
EXPECT_TRUE(config.SdfFile().empty());
EXPECT_TRUE(config.SdfString().empty());
}
43 changes: 43 additions & 0 deletions src/Server_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -295,6 +295,49 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(SdfServerConfig))
EXPECT_FALSE(server.HasEntity("bad", 1));
}

/////////////////////////////////////////////////
TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(SdfRootServerConfig))
{
ignition::gazebo::ServerConfig serverConfig;

serverConfig.SetSdfString(TestWorldSansPhysics::World());
EXPECT_TRUE(serverConfig.SdfFile().empty());
EXPECT_FALSE(serverConfig.SdfString().empty());

serverConfig.SetSdfFile(common::joinPaths(PROJECT_SOURCE_PATH,
"test", "worlds", "air_pressure.sdf"));
EXPECT_FALSE(serverConfig.SdfFile().empty());
EXPECT_TRUE(serverConfig.SdfString().empty());

sdf::Root root;
root.Load(common::joinPaths(PROJECT_SOURCE_PATH,
"test", "worlds", "shapes.sdf"));

// Setting the SDF Root should override the string and file.
serverConfig.SetSdfRoot(root);

EXPECT_TRUE(serverConfig.SdfRoot());
EXPECT_TRUE(serverConfig.SdfFile().empty());
EXPECT_TRUE(serverConfig.SdfString().empty());

gazebo::Server server(serverConfig);
EXPECT_FALSE(server.Running());
EXPECT_FALSE(*server.Running(0));
EXPECT_TRUE(*server.Paused());
EXPECT_EQ(0u, *server.IterationCount());
EXPECT_EQ(24u, *server.EntityCount());
EXPECT_EQ(3u, *server.SystemCount());

EXPECT_TRUE(server.HasEntity("box"));
EXPECT_FALSE(server.HasEntity("box", 1));
EXPECT_TRUE(server.HasEntity("sphere"));
EXPECT_TRUE(server.HasEntity("cylinder"));
EXPECT_TRUE(server.HasEntity("capsule"));
EXPECT_TRUE(server.HasEntity("ellipsoid"));
EXPECT_FALSE(server.HasEntity("bad", 0));
EXPECT_FALSE(server.HasEntity("bad", 1));
}

/////////////////////////////////////////////////
TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(ServerConfigLogRecord))
{
Expand Down
77 changes: 77 additions & 0 deletions src/Util.cc
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,9 @@
#include <ignition/transport/TopicUtils.hh>
#include <sdf/Types.hh>

#include <ignition/fuel_tools/Interface.hh>
#include <ignition/fuel_tools/ClientConfig.hh>

#include "ignition/gazebo/components/Actor.hh"
#include "ignition/gazebo/components/Collision.hh"
#include "ignition/gazebo/components/Joint.hh"
Expand Down Expand Up @@ -579,6 +582,80 @@ std::optional<math::Vector3d> sphericalCoordinates(Entity _entity,
// Return degrees
return math::Vector3d(IGN_RTOD(rad.X()), IGN_RTOD(rad.Y()), rad.Z());
}

//////////////////////////////////////////////////
// Getting the first .sdf file in the path
std::string findFuelResourceSdf(const std::string &_path)
{
if (!common::exists(_path))
return "";

for (common::DirIter file(_path); file != common::DirIter(); ++file)
{
std::string current(*file);
if (!common::isFile(current))
continue;

auto fileName = common::basename(current);
auto fileExtensionIndex = fileName.rfind(".");
auto fileExtension = fileName.substr(fileExtensionIndex + 1);

if (fileExtension == "sdf")
{
return current;
}
}
return "";
}

//////////////////////////////////////////////////
std::string IGNITION_GAZEBO_VISIBLE resolveSdfWorldFile(
const std::string &_sdfFile, const std::string &_fuelResourceCache)
{
std::string filePath;

// Check Fuel if it's a URL
auto sdfUri = common::URI(_sdfFile);
if (sdfUri.Scheme() == "http" || sdfUri.Scheme() == "https")
{
fuel_tools::ClientConfig config;
if (!_fuelResourceCache.empty())
config.SetCacheLocation(_fuelResourceCache);
fuel_tools::FuelClient fuelClient(config);

std::string fuelCachePath;
if (fuelClient.CachedWorld(common::URI(_sdfFile), fuelCachePath))
{
filePath = findFuelResourceSdf(fuelCachePath);
}
else if (auto result = fuelClient.DownloadWorld(
common::URI(_sdfFile), fuelCachePath))
{
filePath = findFuelResourceSdf(fuelCachePath);
}
else
{
ignwarn << "Fuel couldn't download URL [" << _sdfFile
<< "], error: [" << result.ReadableResult() << "]"
<< std::endl;
}
}

if (filePath.empty())
{
common::SystemPaths systemPaths;

// Worlds from environment variable
systemPaths.SetFilePathEnv(kResourcePathEnv);

// Worlds installed with ign-gazebo
systemPaths.AddFilePaths(IGN_GAZEBO_WORLD_INSTALL_DIR);

filePath = systemPaths.FindFile(_sdfFile);
}

return filePath;
}
}
}
}
Expand Down
Loading