Skip to content

Commit

Permalink
Allow using plugin file names environment variables compatible with G…
Browse files Browse the repository at this point in the history
…arden and later

Signed-off-by: Addisu Z. Taddese <[email protected]>
  • Loading branch information
azeey committed Jan 4, 2024
1 parent e0e02c4 commit a0bb757
Show file tree
Hide file tree
Showing 9 changed files with 94 additions and 32 deletions.
18 changes: 15 additions & 3 deletions include/gz/sim/Util.hh
Original file line number Diff line number Diff line change
Expand Up @@ -287,19 +287,31 @@ namespace ignition
std::optional<math::Vector3d> IGNITION_GAZEBO_VISIBLE sphericalCoordinates(
Entity _entity, const EntityComponentManager &_ecm);

/// \brief Environment variable holding resource paths.
/// \brief Environment variable holding resource paths. Prefer using
/// GZ_SIM_RESOURCE_PATH for compatibility with newer versions of Gazebo.
const std::string kResourcePathEnv{"IGN_GAZEBO_RESOURCE_PATH"};
/// \brief Environment variable holding resource paths.
const std::string kResourcePathEnvGzSim{"GZ_SIM_RESOURCE_PATH"};

/// \brief Environment variable used by SDFormat to find URIs inside
/// `<include>`
const std::string kSdfPathEnv{"SDF_PATH"};

/// \brief Environment variable holding server config paths.
/// \brief Environment variable holding server config paths. Prefer using
/// GZ_SIM_SERVER_CONFIG_PATH for compatibility with newer versions of
/// Gazebo.
const std::string kServerConfigPathEnv{"IGN_GAZEBO_SERVER_CONFIG_PATH"};
/// \brief Environment variable holding server config paths.
const std::string kServerConfigPathEnvGzSim{"GZ_SIM_SERVER_CONFIG_PATH"};

/// \brief Environment variable holding paths to custom rendering engine
/// plugins.
/// plugins. Prefer using GZ_SIM_RENDER_ENGINE_PATH for compatibility with
/// newer versions of Gazebo
const std::string kRenderPluginPathEnv{"IGN_GAZEBO_RENDER_ENGINE_PATH"};
/// \brief Environment variable holding paths to custom rendering engine
/// plugins.
const std::string kRenderPluginPathEnvGzSim{"GZ_SIM_RENDER_ENGINE_PATH"};

}
}
}
Expand Down
5 changes: 2 additions & 3 deletions src/Conversions.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1713,9 +1713,8 @@ msgs::ParticleEmitter ignition::gazebo::convert(const sdf::ParticleEmitter &_in)
{
std::string path = asFullPath(_in.ColorRangeImage(), _in.FilePath());

common::SystemPaths systemPaths;
systemPaths.SetFilePathEnv(kResourcePathEnv);
std::string absolutePath = systemPaths.FindFile(path);
const std::string absolutePath =
common::SystemPaths::LocateLocalFile(path, gazebo::resourcePaths());

if (!absolutePath.empty())
out.mutable_color_range_image()->set_data(absolutePath);
Expand Down
54 changes: 35 additions & 19 deletions src/ServerConfig.cc
Original file line number Diff line number Diff line change
Expand Up @@ -922,30 +922,26 @@ ignition::gazebo::parsePluginsFromString(const std::string &_str)
std::list<ServerConfig::PluginInfo>
ignition::gazebo::loadPluginInfo(bool _isPlayback)
{
std::list<ServerConfig::PluginInfo> ret;

// 1. Check contents of environment variable
std::string envConfig;
bool configSet = common::env(kServerConfigPathEnv,
envConfig,
true);

if (configSet)
auto parsePlugins = [](const std::string &_serverConfigPathEnv,
const std::string &_envConfig)
{
if (common::exists(envConfig))
std::list<ServerConfig::PluginInfo> ret;
if (common::exists(_envConfig))
{
// Parse configuration stored in environment variable
ret = gz::sim::parsePluginsFromFile(envConfig);
ret = gz::sim::parsePluginsFromFile(_envConfig);
if (ret.empty())
{
// This may be desired behavior, but warn just in case.
// Some users may want to defer all loading until later
// during runtime.
ignwarn << kServerConfigPathEnv
<< " set but no plugins found\n";
ignwarn << _serverConfigPathEnv
<< " set but no plugins found\n";
}
igndbg << "Loaded (" << ret.size() << ") plugins from file " <<
"[" << envConfig << "]\n";
"[" << _envConfig << "]\n";

return ret;
}
Expand All @@ -954,11 +950,31 @@ ignition::gazebo::loadPluginInfo(bool _isPlayback)
// This may be desired behavior, but warn just in case.
// Some users may want to defer all loading until late
// during runtime.
ignwarn << kServerConfigPathEnv
<< " set but no file found,"
<< " no plugins loaded\n";
ignwarn << _serverConfigPathEnv
<< " set but no file found,"
<< " no plugins loaded\n";
return ret;
}
};

{
std::string envConfig;
bool configSet = common::env(kServerConfigPathEnv, envConfig, true);
if (configSet)
{
return parsePlugins(kServerConfigPathEnv, envConfig);
}
}

// Process the gz-sim environment variable the same way. If the IGN variable
// is set, it will have precedence.
{
std::string envConfig;
bool configSet = common::env(kServerConfigPathEnvGzSim, envConfig, true);
if (configSet)
{
return parsePlugins(kServerConfigPathEnvGzSim, envConfig);
}
}

std::string configFilename;
Expand Down Expand Up @@ -989,7 +1005,7 @@ ignition::gazebo::loadPluginInfo(bool _isPlayback)
{
ignerr << "Failed to create directory [" << defaultConfigDir
<< "]." << std::endl;
return ret;
return {};
}

if (!common::exists(installedConfig))
Expand All @@ -998,14 +1014,14 @@ ignition::gazebo::loadPluginInfo(bool _isPlayback)
<< "] to default config [" << defaultConfig << "]."
<< "(file " << installedConfig << " doesn't exist)"
<< std::endl;
return ret;
return {};
}
else if (!common::copyFile(installedConfig, defaultConfig))
{
ignerr << "Failed to copy installed config [" << installedConfig
<< "] to default config [" << defaultConfig << "]."
<< std::endl;
return ret;
return {};
}
else
{
Expand All @@ -1015,7 +1031,7 @@ ignition::gazebo::loadPluginInfo(bool _isPlayback)
}
}

ret = gz::sim::parsePluginsFromFile(defaultConfig);
const auto ret = gz::sim::parsePluginsFromFile(defaultConfig);

if (ret.empty())
{
Expand Down
2 changes: 1 addition & 1 deletion src/ServerPrivate.hh
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ namespace ignition
/// string and return value of false will be used if the resource could
/// not be found.
///
/// Fuel will be checked and then the GZ_GAZEBO_RESOURCE_PATH environment
/// Fuel will be checked and then the IGN_GAZEBO_RESOURCE_PATH environment
/// variable paths. This service will not check for files relative to
/// working directory of the Gazebo server.
///
Expand Down
23 changes: 21 additions & 2 deletions src/SystemLoader.cc
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,14 @@ class ignition::gazebo::SystemLoaderPrivate
gz::common::SystemPaths systemPaths;
systemPaths.SetPluginPathEnv(pluginPathEnv);

// Also add GZ_SYSTEM_SIM_PLUGIN_PATH for compatibility with Garden and
// later.
for (const auto &path :
common::SystemPaths::PathsFromEnv(this->pluginPathEnvGzSim))
{
systemPaths.AddPluginPaths(path);
}

for (const auto &path : this->systemPluginPaths)
systemPaths.AddPluginPaths(path);

Expand All @@ -62,14 +70,22 @@ class ignition::gazebo::SystemLoaderPrivate
public: bool InstantiateSystemPlugin(const sdf::Plugin &_sdfPlugin,
ignition::plugin::PluginPtr &_gzPlugin)
{
const std::string gzSimPrefix{"gz-sim"};
auto filename = _sdfPlugin.Filename();
auto pos = filename.find(gzSimPrefix);
if (pos == 0u)
{
filename.replace(pos, gzSimPrefix.size(), "ignition-gazebo");
}

std::list<std::string> paths = this->PluginPaths();
common::SystemPaths systemPaths;
for (const auto &p : paths)
{
systemPaths.AddPluginPaths(p);
}

auto pathToLib = systemPaths.FindSharedLibrary(_sdfPlugin.Filename());
auto pathToLib = systemPaths.FindSharedLibrary(filename);
if (pathToLib.empty())
{
// We assume gz::sim corresponds to the levels feature
Expand Down Expand Up @@ -125,8 +141,11 @@ class ignition::gazebo::SystemLoaderPrivate
return true;
}

// Default plugin search path environment variable
// Default plugin search path environment variable. Prefer
// GZ_SYSTEM_SIM_PLUGIN_PATH for compatibility with future versions of Gazebo.
public: std::string pluginPathEnv{"IGN_GAZEBO_SYSTEM_PLUGIN_PATH"};
// Default plugin search path environment variable
public: std::string pluginPathEnvGzSim{"GZ_SIM_SYSTEM_PLUGIN_PATH"};

/// \brief Plugin loader instace
public: gz::plugin::Loader loader;
Expand Down
9 changes: 9 additions & 0 deletions src/Util.cc
Original file line number Diff line number Diff line change
Expand Up @@ -411,6 +411,11 @@ std::vector<std::string> resourcePaths()
gzPaths = common::Split(gzPathCStr, common::SystemPaths::Delimiter());
}

const auto gzSimResourcePaths =
common::SystemPaths::PathsFromEnv(kResourcePathEnvGzSim);
gzPaths.insert(gzPaths.begin(), gzSimResourcePaths.begin(),
gzSimResourcePaths.end());

gzPaths.erase(std::remove_if(gzPaths.begin(), gzPaths.end(),
[](const std::string &_path)
{
Expand Down Expand Up @@ -447,6 +452,10 @@ void addResourcePaths(const std::vector<std::string> &_paths)
{
gzPaths = common::Split(gzPathCStr, common::SystemPaths::Delimiter());
}
const auto gzSimResourcePaths =
common::SystemPaths::PathsFromEnv(kResourcePathEnvGzSim);
gzPaths.insert(gzPaths.begin(), gzSimResourcePaths.begin(),
gzSimResourcePaths.end());

// Add new paths to gzPaths
for (const auto &path : _paths)
Expand Down
7 changes: 6 additions & 1 deletion src/cmd/cmdgazebo.rb.in
Original file line number Diff line number Diff line change
Expand Up @@ -160,9 +160,14 @@ COMMANDS = { 'gazebo' =>
"Environment variables: \n"\
" IGN_GAZEBO_RESOURCE_PATH Colon separated paths used to locate \n"\
" resources such as worlds and models. \n\n"\
" GZ_SIM_RESOURCE_PATH Colon separated paths used to locate \n"\
" resources such as worlds and models. \n\n"\
" IGN_GAZEBO_SYSTEM_PLUGIN_PATH Colon separated paths used to \n"\
" locate system plugins. \n\n"\
" GZ_SIM_SYSTEM_PLUGIN_PATH Colon separated paths used to \n"\
" locate system plugins. \n\n"\
" IGN_GAZEBO_SERVER_CONFIG_PATH Path to server configuration file. \n\n"\
" GZ_SIM_SERVER_CONFIG_PATH Path to server configuration file. \n\n"\
" IGN_GUI_PLUGIN_PATH Colon separated paths used to locate GUI \n"\
" plugins. \n\n"\
" GZ_GUI_RESOURCE_PATH Colon separated paths used to locate GUI \n"\
Expand Down Expand Up @@ -412,7 +417,7 @@ has properly set the DYLD_LIBRARY_PATH environment variables."
# If not, then first check the IGN_GAZEBO_RESOURCE_PATH environment
# variable, then the configuration path from the launch library.
else
resourcePathEnv = ENV['IGN_GAZEBO_RESOURCE_PATH']
resourcePathEnv = "#{ENV['IGN_GAZEBO_RESOURCE_PATH']}:#{ENV['GZ_SIM_RESOURCE_PATH']}"
if !resourcePathEnv.nil?
resourcePaths = resourcePathEnv.split(':')
for resourcePath in resourcePaths
Expand Down
3 changes: 3 additions & 0 deletions src/rendering/RenderUtil.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2555,6 +2555,9 @@ void RenderUtil::InitRenderEnginePluginPaths()
common::SystemPaths pluginPath;
pluginPath.SetPluginPathEnv(kRenderPluginPathEnv);
rendering::setPluginPaths(pluginPath.PluginPaths());

rendering::setPluginPaths(
common::SystemPaths::PathsFromEnv(kRenderPluginPathEnvGzSim));
}

/////////////////////////////////////////////////
Expand Down
5 changes: 2 additions & 3 deletions src/systems/particle_emitter/ParticleEmitter.cc
Original file line number Diff line number Diff line change
Expand Up @@ -250,9 +250,8 @@ void ParticleEmitter::Configure(const Entity &_entity,
auto colorRangeImagePath = _sdf->Get<std::string>("color_range_image");
auto path = asFullPath(colorRangeImagePath, modelPath.value());

common::SystemPaths systemPaths;
systemPaths.SetFilePathEnv(kResourcePathEnv);
auto absolutePath = systemPaths.FindFile(path);
const std::string absolutePath =
common::SystemPaths::LocateLocalFile(path, gazebo::resourcePaths());

this->dataPtr->emitter.mutable_color_range_image()->set_data(
absolutePath);
Expand Down

0 comments on commit a0bb757

Please sign in to comment.