Skip to content

Commit

Permalink
cherry pick aef3020
Browse files Browse the repository at this point in the history
Signed-off-by: Ian Chen <[email protected]>
  • Loading branch information
iche033 committed Sep 1, 2022
1 parent 545b364 commit 3394a23
Show file tree
Hide file tree
Showing 11 changed files with 551 additions and 38 deletions.
8 changes: 7 additions & 1 deletion include/ignition/gazebo/SystemLoader.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#ifndef IGNITION_GAZEBO_SYSTEMLOADER_HH_
#define IGNITION_GAZEBO_SYSTEMLOADER_HH_

#include <list>
#include <memory>
#include <optional>
#include <string>
Expand Down Expand Up @@ -61,7 +62,8 @@ namespace ignition

/// \brief Load and instantiate system plugin from name/filename.
/// \param[in] _filename Shared library filename to load plugin from.
/// \param[in] _name Class name to be instantiated.
/// \param[in] _name Class name to be instantiated. If empty, the first
/// plugin in the shared library will be loaded.
/// \param[in] _sdf SDF Element describing plugin instance to be loaded.
/// \returns Shared pointer to system instance or nullptr.
/// \note This will be deprecated in Gazebo 7 (Garden), please the use
Expand All @@ -81,6 +83,10 @@ namespace ignition
/// \returns A pretty string
public: std::string PrettyStr() const;

/// \brief Get the plugin search paths used for loading system plugins
/// \return Paths to search for plugins
public: std::list<std::string> PluginPaths() const;

/// \brief Pointer to private data.
private: std::unique_ptr<SystemLoaderPrivate> dataPtr;
};
Expand Down
1 change: 1 addition & 0 deletions src/ServerConfig.cc
Original file line number Diff line number Diff line change
Expand Up @@ -91,6 +91,7 @@ class ignition::gazebo::ServerConfig::PluginInfoPrivate

/// \brief XML elements associated with this plugin
public: sdf::ElementPtr sdf = nullptr;

};

//////////////////////////////////////////////////
Expand Down
43 changes: 32 additions & 11 deletions src/SystemLoader.cc
Original file line number Diff line number Diff line change
Expand Up @@ -41,8 +41,7 @@ class ignition::gazebo::SystemLoaderPrivate
public: explicit SystemLoaderPrivate() = default;

//////////////////////////////////////////////////
public: bool InstantiateSystemPlugin(const sdf::Plugin &_sdfPlugin,
ignition::plugin::PluginPtr &_gzPlugin)
public: std::list<std::string> PluginPaths() const
{
ignition::common::SystemPaths systemPaths;
systemPaths.SetPluginPathEnv(pluginPathEnv);
Expand All @@ -52,9 +51,24 @@ class ignition::gazebo::SystemLoaderPrivate

std::string homePath;
ignition::common::env(IGN_HOMEDIR, homePath);
systemPaths.AddPluginPaths(homePath + "/.ignition/gazebo/plugins");
systemPaths.AddPluginPaths(common::joinPaths(
homePath, ".ignition", "gazebo", "plugins"));
systemPaths.AddPluginPaths(IGN_GAZEBO_PLUGIN_INSTALL_DIR);

return systemPaths.PluginPaths();
}

//////////////////////////////////////////////////
public: bool InstantiateSystemPlugin(const sdf::Plugin &_sdfPlugin,
ignition::plugin::PluginPtr &_gzPlugin)
{
std::list<std::string> paths = this->PluginPaths();
common::SystemPaths systemPaths;
for (const auto &p : paths)
{
systemPaths.AddPluginPaths(p);
}

auto pathToLib = systemPaths.FindSharedLibrary(_sdfPlugin.Filename());
if (pathToLib.empty())
{
Expand Down Expand Up @@ -85,7 +99,11 @@ class ignition::gazebo::SystemLoaderPrivate
return false;
}

_gzPlugin = this->loader.Instantiate(_sdfPlugin.Name());
// use the first plugin name in the library if not specified
std::string pluginToInstantiate = _sdfPlugin.Name().empty() ?
pluginName : _sdfPlugin.Name();

_gzPlugin = this->loader.Instantiate(pluginToInstantiate);
if (!_gzPlugin)
{
ignerr << "Failed to load system plugin [" << _sdfPlugin.Name() <<
Expand Down Expand Up @@ -129,6 +147,12 @@ SystemLoader::SystemLoader()
//////////////////////////////////////////////////
SystemLoader::~SystemLoader() = default;

//////////////////////////////////////////////////
std::list<std::string> SystemLoader::PluginPaths() const
{
return this->dataPtr->PluginPaths();
}

//////////////////////////////////////////////////
void SystemLoader::AddSystemPluginPath(const std::string &_path)
{
Expand All @@ -141,11 +165,10 @@ std::optional<SystemPluginPtr> SystemLoader::LoadPlugin(
const std::string &_name,
const sdf::ElementPtr &_sdf)
{
if (_filename == "" || _name == "")
if (_filename == "")
{
ignerr << "Failed to instantiate system plugin: empty argument "
"[(filename): " << _filename << "] " <<
"[(name): " << _name << "]." << std::endl;
"[(filename): " << _filename << "] " << std::endl;
return {};
}

Expand Down Expand Up @@ -175,18 +198,16 @@ std::optional<SystemPluginPtr> SystemLoader::LoadPlugin(
{
ignition::plugin::PluginPtr plugin;

if (_plugin.Filename() == "" || _plugin.Name() == "")
if (_plugin.Filename() == "")
{
ignerr << "Failed to instantiate system plugin: empty argument "
"[(filename): " << _plugin.Filename() << "] " <<
"[(name): " << _plugin.Name() << "]." << std::endl;
"[(filename): " << _plugin.Filename() << "] " << std::endl;
return {};
}

auto ret = this->dataPtr->InstantiateSystemPlugin(_plugin, plugin);
if (ret && plugin)
return plugin;

return {};
}

Expand Down
36 changes: 36 additions & 0 deletions src/SystemLoader_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
#include "ignition/gazebo/test_config.hh" // NOLINT(build/include)

using namespace ignition;
using namespace gazebo;

/////////////////////////////////////////////////
TEST(SystemLoader, Constructor)
Expand Down Expand Up @@ -67,3 +68,38 @@ TEST(SystemLoader, EmptyNames)
auto system = sm.LoadPlugin(plugin);
ASSERT_FALSE(system.has_value());
}

/////////////////////////////////////////////////
TEST(SystemLoader, PluginPaths)
{
SystemLoader sm;

// verify that there should exist some default paths
std::list<std::string> paths = sm.PluginPaths();
unsigned int pathCount = paths.size();
EXPECT_LT(0u, pathCount);

// Add test path and verify that the loader now contains this path
auto testBuildPath = common::joinPaths(
std::string(PROJECT_BINARY_PATH), "lib");
sm.AddSystemPluginPath(testBuildPath);
paths = sm.PluginPaths();

// Number of paths should increase by 1
EXPECT_EQ(pathCount + 1, paths.size());

// verify newly added paths exists
bool hasPath = false;
for (const auto &s : paths)
{
// the returned path string may not be exact match due to extra '/'
// appended at the end of the string. So use absPath to generate
// a path string that matches the format returned by joinPaths
if (common::absPath(s) == testBuildPath)
{
hasPath = true;
break;
}
}
EXPECT_TRUE(hasPath);
}
60 changes: 57 additions & 3 deletions src/SystemManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,11 @@
*
*/

#include <list>
#include <set>

#include <ignition/common/StringUtils.hh>

#include "ignition/gazebo/components/SystemPluginInfo.hh"
#include "ignition/gazebo/Conversions.hh"
#include "SystemManager.hh"
Expand All @@ -34,11 +39,15 @@ SystemManager::SystemManager(const SystemLoaderPtr &_systemLoader,
transport::NodeOptions opts;
opts.SetNameSpace(_namespace);
this->node = std::make_unique<transport::Node>(opts);
std::string entitySystemService{"entity/system/add"};
this->node->Advertise(entitySystemService,
std::string entitySystemAddService{"entity/system/add"};
this->node->Advertise(entitySystemAddService,
&SystemManager::EntitySystemAddService, this);
ignmsg << "Serving entity system service on ["
<< "/" << entitySystemService << "]" << std::endl;
<< "/" << entitySystemAddService << "]" << std::endl;

std::string entitySystemInfoService{"system/info"};
this->node->Advertise(entitySystemInfoService,
&SystemManager::EntitySystemInfoService, this);
}

//////////////////////////////////////////////////
Expand Down Expand Up @@ -215,6 +224,51 @@ bool SystemManager::EntitySystemAddService(const msgs::EntityPlugin_V &_req,
return true;
}

//////////////////////////////////////////////////
bool SystemManager::EntitySystemInfoService(const msgs::Empty &,
msgs::EntityPlugin_V &_res)
{
// loop through all files in paths and populate the list of
// plugin libraries.
std::list<std::string> paths = this->systemLoader->PluginPaths();
std::set<std::string> filenames;
for (const auto &p : paths)
{
if (common::exists(p))
{
for (common::DirIter file(p);
file != common::DirIter(); ++file)
{
std::string current(*file);
std::string filename = common::basename(current);
if (common::isFile(current) &&
(common::EndsWith(filename, ".so") ||
common::EndsWith(filename, ".dll") ||
common::EndsWith(filename, ".dylib")))
{
// remove extension and lib prefix
size_t extensionIndex = filename.rfind(".");
std::string nameWithoutExtension =
filename.substr(0, extensionIndex);
if (common::StartsWith(nameWithoutExtension, "lib"))
{
nameWithoutExtension = nameWithoutExtension.substr(3);
}
filenames.insert(nameWithoutExtension);
}
}
}
}

for (const auto &fn : filenames)
{
auto plugin = _res.add_plugins();
plugin->set_filename(fn);
}

return true;
}

//////////////////////////////////////////////////
void SystemManager::ProcessPendingEntitySystems()
{
Expand Down
8 changes: 8 additions & 0 deletions src/SystemManager.hh
Original file line number Diff line number Diff line change
Expand Up @@ -142,6 +142,14 @@ namespace ignition
private: bool EntitySystemAddService(const msgs::EntityPlugin_V &_req,
msgs::Boolean &_res);

/// \brief Callback for entity info system service.
/// \param[in] _req Empty request message
/// \param[out] _res Response containing a list of plugin names
/// and filenames
/// \return True if request received.
private: bool EntitySystemInfoService(const msgs::Empty &_req,
msgs::EntityPlugin_V &_res);

/// \brief All the systems.
private: std::vector<SystemInternal> systems;

Expand Down
Loading

0 comments on commit 3394a23

Please sign in to comment.