Skip to content

Commit

Permalink
Add entity and sdf parameters to Server's AddSystem interface
Browse files Browse the repository at this point in the history
Signed-off-by: Gabriel Arjones <[email protected]>
  • Loading branch information
g-arjones committed Feb 29, 2024
1 parent 633ce72 commit bf4a8db
Show file tree
Hide file tree
Showing 3 changed files with 116 additions and 7 deletions.
45 changes: 45 additions & 0 deletions include/gz/sim/Server.hh
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,8 @@
#include <gz/sim/Export.hh>
#include <gz/sim/ServerConfig.hh>
#include <gz/sim/SystemPluginPtr.hh>
#include <sdf/Element.hh>
#include <sdf/Plugin.hh>

namespace gz
{
Expand Down Expand Up @@ -225,14 +227,57 @@ namespace gz
const SystemPluginPtr &_system,
const unsigned int _worldIndex = 0);

/// \brief Add a System to the server. The server must not be running when
/// calling this.
/// \param[in] _system system to be added
/// \param[in] _entity Entity of system to be added.
/// \param[in] _sdf Pointer to the SDF element of a <plugin> tag with
/// configuration options for the system being added.
/// \param[in] _worldIndex Index of the world to query.
/// \return Whether the system was added successfully, or std::nullopt
/// if _worldIndex is invalid.
public: std::optional<bool> AddSystem(
const SystemPluginPtr &_system,
std::optional<Entity> _entity,
std::optional<std::shared_ptr<const sdf::Element>> _sdf,
const unsigned int _worldIndex = 0);

/// \brief Add a System to the server. The server must not be running when
/// calling this.
/// \param[in] _plugin system plugin to be added with any additional XML
/// contents.
/// \param[in] _entity Entity of system to be added.
/// \param[in] _worldIndex Index of the world to query.
/// \return Whether the system was added successfully, or std::nullopt
/// if _worldIndex is invalid.
public: std::optional<bool> AddSystem(
const sdf::Plugin &_plugin,
std::optional<Entity> _entity,
const unsigned int _worldIndex = 0);

/// \brief Add a System to the server. The server must not be running when
/// calling this.
/// \param[in] _system System to be added
/// \param[in] _worldIndex Index of the world to add to.
/// \return Whether the system was added successfully, or std::nullopt
/// if _worldIndex is invalid.
public: std::optional<bool> AddSystem(
const std::shared_ptr<System> &_system,
const unsigned int _worldIndex = 0);

/// \brief Add a System to the server. The server must not be running when
/// calling this.
/// \param[in] _system System to be added
/// \param[in] _entity Entity of system to be added.
/// \param[in] _sdf Pointer to the SDF element of a <plugin> tag with
/// configuration options for the system being added
/// \param[in] _worldIndex Index of the world to add to.
/// \return Whether the system was added successfully, or std::nullopt
/// if _worldIndex is invalid.
public: std::optional<bool> AddSystem(
const std::shared_ptr<System> &_system,
std::optional<Entity> _entity,
std::optional<std::shared_ptr<const sdf::Element>> _sdf,
const unsigned int _worldIndex = 0);

/// \brief Get an Entity based on a name.
Expand Down
37 changes: 35 additions & 2 deletions src/Server.cc
Original file line number Diff line number Diff line change
Expand Up @@ -352,6 +352,29 @@ std::optional<size_t> Server::SystemCount(const unsigned int _worldIndex) const
//////////////////////////////////////////////////
std::optional<bool> Server::AddSystem(const SystemPluginPtr &_system,
const unsigned int _worldIndex)
{
return this->AddSystem(_system, std::nullopt, std::nullopt, _worldIndex);
}

//////////////////////////////////////////////////
std::optional<bool> Server::AddSystem(const sdf::Plugin &_plugin,
std::optional<Entity> _entity,
const unsigned int _worldIndex)
{
auto system = this->dataPtr->systemLoader->LoadPlugin(_plugin);
if (system)
{
return this->AddSystem(system.value(), _entity, _plugin.ToElement(), _worldIndex);
}
return false;
}

//////////////////////////////////////////////////
std::optional<bool> Server::AddSystem(
const SystemPluginPtr &_system,
std::optional<Entity> _entity,
std::optional<std::shared_ptr<const sdf::Element>> _sdf,
const unsigned int _worldIndex)
{
// Check the current state, and return early if preconditions are not met.
std::lock_guard<std::mutex> lock(this->dataPtr->runMutex);
Expand All @@ -364,7 +387,7 @@ std::optional<bool> Server::AddSystem(const SystemPluginPtr &_system,

if (_worldIndex < this->dataPtr->simRunners.size())
{
this->dataPtr->simRunners[_worldIndex]->AddSystem(_system);
this->dataPtr->simRunners[_worldIndex]->AddSystem(_system, _entity, _sdf);
return true;
}

Expand All @@ -374,6 +397,16 @@ std::optional<bool> Server::AddSystem(const SystemPluginPtr &_system,
//////////////////////////////////////////////////
std::optional<bool> Server::AddSystem(const std::shared_ptr<System> &_system,
const unsigned int _worldIndex)
{
return this->AddSystem(_system, std::nullopt, std::nullopt, _worldIndex);
}

//////////////////////////////////////////////////
std::optional<bool> Server::AddSystem(
const std::shared_ptr<System> &_system,
std::optional<Entity> _entity,
std::optional<std::shared_ptr<const sdf::Element>> _sdf,
const unsigned int _worldIndex)
{
std::lock_guard<std::mutex> lock(this->dataPtr->runMutex);
if (this->dataPtr->running)
Expand All @@ -384,7 +417,7 @@ std::optional<bool> Server::AddSystem(const std::shared_ptr<System> &_system,

if (_worldIndex < this->dataPtr->simRunners.size())
{
this->dataPtr->simRunners[_worldIndex]->AddSystem(_system);
this->dataPtr->simRunners[_worldIndex]->AddSystem(_system, _entity, _sdf);
return true;
}

Expand Down
41 changes: 36 additions & 5 deletions src/Server_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -625,17 +625,48 @@ TEST_P(ServerFixture, GZ_UTILS_TEST_DISABLED_ON_WIN32(RunOnceUnpaused))
auto mockSystemPlugin = systemLoader.LoadPlugin(sdfPlugin);
ASSERT_TRUE(mockSystemPlugin.has_value());

// Check that it was loaded
const size_t systemCount = *server.SystemCount();
EXPECT_TRUE(*server.AddSystem(mockSystemPlugin.value()));
EXPECT_EQ(systemCount + 1, *server.SystemCount());

// Query the interface from the plugin
auto system = mockSystemPlugin.value()->QueryInterface<sim::System>();
EXPECT_NE(system, nullptr);
auto mockSystem = dynamic_cast<sim::MockSystem*>(system);
EXPECT_NE(mockSystem, nullptr);

Entity entity = server.EntityByName("default").value();
size_t configureCallCount = 0;
auto configureCallback = [&sdfPlugin, &entity, &configureCallCount](
const Entity &_entity,
const std::shared_ptr<const sdf::Element> &_sdf,
EntityComponentManager &,
EventManager &)
{
configureCallCount++;
EXPECT_EQ(entity, _entity);
EXPECT_EQ(sdfPlugin.ToElement()->ToString(""), _sdf->ToString(""));
};

mockSystem->configureCallback = configureCallback;
const size_t systemCount = *server.SystemCount();
EXPECT_TRUE(
*server.AddSystem(
mockSystemPlugin.value(), entity, sdfPlugin.ToElement()
));

// Add pointer
auto mockSystemPtr = std::make_shared<MockSystem>();
mockSystemPtr->configureCallback = configureCallback;
EXPECT_TRUE(*server.AddSystem(mockSystemPtr, entity, sdfPlugin.ToElement()));

// Add an sdf::Plugin
EXPECT_TRUE(*server.AddSystem(sdfPlugin, entity));

// Fail if plugin is invalid
sdf::Plugin invalidPlugin("foo_plugin", "foo::systems::FooPlugin");
EXPECT_FALSE(*server.AddSystem(invalidPlugin, entity));

// Check that it was loaded
EXPECT_EQ(systemCount + 3, *server.SystemCount());
EXPECT_EQ(2u, configureCallCount);

// No steps should have been executed
EXPECT_EQ(0u, mockSystem->preUpdateCallCount);
EXPECT_EQ(0u, mockSystem->updateCallCount);
Expand Down

0 comments on commit bf4a8db

Please sign in to comment.