Skip to content

Commit

Permalink
PR feedback
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <louise@openrobotics.org>
  • Loading branch information
chapulina committed Jul 28, 2021
1 parent 7b2ab88 commit d8c6047
Show file tree
Hide file tree
Showing 8 changed files with 79 additions and 78 deletions.
10 changes: 5 additions & 5 deletions include/ignition/gazebo/Server.hh
Original file line number Diff line number Diff line change
Expand Up @@ -220,13 +220,13 @@ namespace ignition
const unsigned int _worldIndex = 0);

/// \brief Add a System to the server. The server must not be running when
/// calling this. The server does not take ownership of the pointer and
/// assumes that the pointer is valid during the server's lifetime.
/// \param[in] _system system to be added
/// \param[in] _worldIndex Index of the world to query.
/// 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(System *_system,
public: std::optional<bool> AddSystem(
const std::shared_ptr<System> &_system,
const unsigned int _worldIndex = 0);

/// \brief Get an Entity based on a name.
Expand Down
2 changes: 1 addition & 1 deletion src/Server.cc
Original file line number Diff line number Diff line change
Expand Up @@ -355,7 +355,7 @@ std::optional<bool> Server::AddSystem(const SystemPluginPtr &_system,
}

//////////////////////////////////////////////////
std::optional<bool> Server::AddSystem(System *_system,
std::optional<bool> Server::AddSystem(const std::shared_ptr<System> &_system,
const unsigned int _worldIndex)
{
std::lock_guard<std::mutex> lock(this->dataPtr->runMutex);
Expand Down
10 changes: 5 additions & 5 deletions src/Server_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -733,8 +733,8 @@ TEST_P(ServerFixture, AddSystemWhileRunning)
EXPECT_EQ(3u, *server.SystemCount());

// Add system pointer
auto mockSystem = std::make_unique<MockSystem>();
result = server.AddSystem(mockSystem.get());
auto mockSystem = std::make_shared<MockSystem>();
result = server.AddSystem(mockSystem);
ASSERT_TRUE(result.has_value());
EXPECT_FALSE(result.value());
EXPECT_EQ(3u, *server.SystemCount());
Expand Down Expand Up @@ -778,10 +778,10 @@ TEST_P(ServerFixture, AddSystemAfterLoad)
EXPECT_EQ(1u, mockSystem->configureCallCount);

// Add system pointer
auto mockSystemLocal = std::make_unique<MockSystem>();
auto mockSystemLocal = std::make_shared<MockSystem>();
EXPECT_EQ(0u, mockSystemLocal->configureCallCount);

EXPECT_TRUE(server.AddSystem(mockSystemLocal.get()));
EXPECT_TRUE(server.AddSystem(mockSystemLocal));
EXPECT_EQ(5u, *server.SystemCount());
EXPECT_EQ(1u, mockSystemLocal->configureCallCount);

Expand All @@ -805,7 +805,7 @@ TEST_P(ServerFixture, AddSystemAfterLoad)
auto result = server.AddSystem(mockSystemPlugin.value(), 100);
EXPECT_FALSE(result.has_value());

result = server.AddSystem(mockSystemLocal.get(), 100);
result = server.AddSystem(mockSystemLocal, 100);
EXPECT_FALSE(result.has_value());
}

Expand Down
85 changes: 42 additions & 43 deletions src/SimulationRunner.cc
Original file line number Diff line number Diff line change
Expand Up @@ -416,6 +416,48 @@ void SimulationRunner::PublishStats()
this->rootClockPub.Publish(clockMsg);
}

//////////////////////////////////////////////////
void SimulationRunner::AddSystem(const SystemPluginPtr &_system,
std::optional<Entity> _entity,
std::optional<std::shared_ptr<const sdf::Element>> _sdf)
{
this->AddSystemImpl(SystemInternal(_system), _entity, _sdf);
}

//////////////////////////////////////////////////
void SimulationRunner::AddSystem(
const std::shared_ptr<System> &_system,
std::optional<Entity> _entity,
std::optional<std::shared_ptr<const sdf::Element>> _sdf)
{
this->AddSystemImpl(SystemInternal(_system), _entity, _sdf);
}

//////////////////////////////////////////////////
void SimulationRunner::AddSystemImpl(
SystemInternal _system,
std::optional<Entity> _entity,
std::optional<std::shared_ptr<const sdf::Element>> _sdf)
{
// Call configure
if (_system.configure)
{
// Default to world entity and SDF
auto entity = _entity.has_value() ? _entity.value()
: worldEntity(this->entityCompMgr);
auto sdf = _sdf.has_value() ? _sdf.value() : this->sdfWorld->Element();

_system.configure->Configure(
entity, sdf,
this->entityCompMgr,
this->eventMgr);
}

// Update callbacks will be handled later, add to queue
std::lock_guard<std::mutex> lock(this->pendingSystemsMutex);
this->pendingSystems.push_back(_system);
}

/////////////////////////////////////////////////
void SimulationRunner::AddSystemToRunner(SystemInternal _system)
{
Expand Down Expand Up @@ -785,49 +827,6 @@ void SimulationRunner::Step(const UpdateInfo &_info)
this->entityCompMgr.SetAllComponentsUnchanged();
}

//////////////////////////////////////////////////
void SimulationRunner::AddSystem(
const SystemPluginPtr &_system,
std::optional<Entity> _entity,
std::optional<sdf::ElementPtr> _sdf)
{
this->AddSystemImpl(SystemInternal(_system), _entity, _sdf);
}

//////////////////////////////////////////////////
void SimulationRunner::AddSystem(
System *_system,
std::optional<Entity> _entity,
std::optional<sdf::ElementPtr> _sdf)
{
this->AddSystemImpl(SystemInternal(_system), _entity, _sdf);
}

//////////////////////////////////////////////////
void SimulationRunner::AddSystemImpl(
SystemInternal _system,
std::optional<Entity> _entity,
std::optional<sdf::ElementPtr> _sdf)
{
// Call configure
if (_system.configure)
{
// Default to world entity and SDF
auto entity = _entity.has_value() ? _entity.value()
: worldEntity(this->entityCompMgr);
auto sdf = _sdf.has_value() ? _sdf.value() : this->sdfWorld->Element();

_system.configure->Configure(
entity, sdf,
this->entityCompMgr,
this->eventMgr);
}

// Update callbacks will be handled later, add to queue
std::lock_guard<std::mutex> lock(this->pendingSystemsMutex);
this->pendingSystems.push_back(_system);
}

//////////////////////////////////////////////////
void SimulationRunner::LoadPlugin(const Entity _entity,
const std::string &_fname,
Expand Down
27 changes: 17 additions & 10 deletions src/SimulationRunner.hh
Original file line number Diff line number Diff line change
Expand Up @@ -107,12 +107,13 @@ namespace ignition

/// \brief Constructor
/// \param[in] _system Pointer to a system.
public: explicit SystemInternal(System *_system)
: system(_system),
configure(dynamic_cast<ISystemConfigure *>(_system)),
preupdate(dynamic_cast<ISystemPreUpdate *>(_system)),
update(dynamic_cast<ISystemUpdate *>(_system)),
postupdate(dynamic_cast<ISystemPostUpdate *>(_system))
public: explicit SystemInternal(const std::shared_ptr<System> &_system)
: systemShared(_system),
system(_system.get()),
configure(dynamic_cast<ISystemConfigure *>(_system.get())),
preupdate(dynamic_cast<ISystemPreUpdate *>(_system.get())),
update(dynamic_cast<ISystemUpdate *>(_system.get())),
postupdate(dynamic_cast<ISystemPostUpdate *>(_system.get()))
{
}

Expand All @@ -121,6 +122,10 @@ namespace ignition
/// This will be null if the system wasn't loaded from a plugin.
public: SystemPluginPtr systemPlugin;

/// \brief Pointer to a system.
/// This will be null if the system wasn't loaded from a pointer.
public: std::shared_ptr<System> systemShared{nullptr};

/// \brief Access this system via the `System` interface
public: System *system = nullptr;

Expand Down Expand Up @@ -189,7 +194,8 @@ namespace ignition
/// SDF of the entire world.
public: void AddSystem(const SystemPluginPtr &_system,
std::optional<Entity> _entity = std::nullopt,
std::optional<sdf::ElementPtr> _sdf = std::nullopt);
std::optional<std::shared_ptr<const sdf::Element>> _sdf =
std::nullopt);

/// \brief Add system after the simulation runner has been instantiated
/// \note This actually adds system to a queue. The system is added to the
Expand All @@ -200,9 +206,10 @@ namespace ignition
/// doesn't connect to an entity.
/// \param[in] _sdf Pointer to the SDF of the entity. Nullopt defaults to
/// world.
public: void AddSystem(System *_system,
public: void AddSystem(const std::shared_ptr<System> &_system,
std::optional<Entity> _entity = std::nullopt,
std::optional<sdf::ElementPtr> _sdf = std::nullopt);
std::optional<std::shared_ptr<const sdf::Element>> _sdf =
std::nullopt);

/// \brief Update all the systems
public: void UpdateSystems();
Expand Down Expand Up @@ -424,7 +431,7 @@ namespace ignition
/// \param[in] _sdf SDF received from AddSystem.
private: void AddSystemImpl(SystemInternal _system,
std::optional<Entity> _entity = std::nullopt,
std::optional<sdf::ElementPtr> _sdf = std::nullopt);
std::optional<std::shared_ptr<const sdf::Element>> _sdf = std::nullopt);

/// \brief This is used to indicate that a stop event has been received.
private: std::atomic<bool> stopReceived{false};
Expand Down
19 changes: 7 additions & 12 deletions test/helpers/Relay.hh
Original file line number Diff line number Diff line change
Expand Up @@ -53,41 +53,36 @@ class Relay
/// \brief Constructor
public: Relay()
{
this->mockSystem = std::make_unique<MockSystem>();
EXPECT_NE(nullptr, this->mockSystem);

this->systemPtr = this->mockSystem.get();
this->systemPtr = std::make_shared<MockSystem>();
EXPECT_NE(nullptr, this->systemPtr);
}

/// \brief Wrapper around system's pre-update callback
/// \param[in] _cb Function to be called every pre-update
public: Relay &OnPreUpdate(MockSystem::CallbackType _cb)
{
this->mockSystem->preUpdateCallback = std::move(_cb);
this->systemPtr->preUpdateCallback = std::move(_cb);
return *this;
}

/// \brief Wrapper around system's update callback
/// \param[in] _cb Function to be called every update
public: Relay &OnUpdate(MockSystem::CallbackType _cb)
{
this->mockSystem->updateCallback = std::move(_cb);
this->systemPtr->updateCallback = std::move(_cb);
return *this;
}

/// \brief Wrapper around system's post-update callback
/// \param[in] _cb Function to be called every post-update
public: Relay &OnPostUpdate(MockSystem::CallbackTypeConst _cb)
{
this->mockSystem->postUpdateCallback = std::move(_cb);
this->systemPtr->postUpdateCallback = std::move(_cb);
return *this;
}

/// \brief Pointer to underlying mock interface
public: std::unique_ptr<MockSystem> mockSystem{nullptr};

/// \brief Underlying raw pointer, for convenience
public: MockSystem *systemPtr{nullptr};
/// \brief Pointer to system
public: std::shared_ptr<MockSystem> systemPtr{nullptr};
};
}
}
Expand Down
2 changes: 1 addition & 1 deletion test/integration/level_manager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ class ModelMover: public test::Relay
public: explicit ModelMover(Entity _entity): test::Relay(), entity(_entity)
{
using namespace std::placeholders;
this->mockSystem->preUpdateCallback =
this->systemPtr->preUpdateCallback =
std::bind(&ModelMover::MoveModel, this, _1, _2);
}

Expand Down
2 changes: 1 addition & 1 deletion test/integration/level_manager_runtime_performers.cc
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ class ModelMover: public test::Relay
public: explicit ModelMover(Entity _entity): test::Relay(), entity(_entity)
{
using namespace std::placeholders;
this->mockSystem->preUpdateCallback =
this->systemPtr->preUpdateCallback =
std::bind(&ModelMover::MoveModel, this, _1, _2);
}

Expand Down

0 comments on commit d8c6047

Please sign in to comment.