Skip to content
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

Add support for simulation reset via a publicly callable API #2648

Open
wants to merge 9 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all 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
7 changes: 7 additions & 0 deletions include/gz/sim/Server.hh
Original file line number Diff line number Diff line change
Expand Up @@ -338,6 +338,13 @@ namespace gz
/// \brief Stop the server. This will stop all running simulations.
public: void Stop();

/// \brief Reset all runners in this simulation
public: void ResetAll();
arjo129 marked this conversation as resolved.
Show resolved Hide resolved
/// \brief Reset a specific runner in this server
/// \param[in] runnerId - The runner which you want to reset
/// \ return False if the runner does not exist, true otherwise.
public: bool Reset(const std::size_t _runnerId);

/// \brief Private data
private: std::unique_ptr<ServerPrivate> dataPtr;
};
Expand Down
6 changes: 5 additions & 1 deletion python/src/gz/sim/Server.cc
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,11 @@ void defineSimServer(pybind11::object module)
.def(
"is_running",
pybind11::overload_cast<>(&gz::sim::Server::Running, pybind11::const_),
"Get whether the server is running.");
"Get whether the server is running.")
.def("reset_all", &gz::sim::Server::ResetAll,
"Resets all simulation runners under this server.")
.def("reset", &gz::sim::Server::Reset,
"Resets a specific simulation runner under this server.");
}
} // namespace python
} // namespace sim
Expand Down
22 changes: 22 additions & 0 deletions src/Server.cc
Original file line number Diff line number Diff line change
Expand Up @@ -485,6 +485,28 @@ bool Server::RequestRemoveEntity(const Entity _entity,
return false;
}

//////////////////////////////////////////////////
void Server::ResetAll()
{
for (auto worldId = 0u;
worldId < this->dataPtr->simRunners.size();
worldId++)
{
this->dataPtr->simRunners[worldId]->Reset(true, false, false);
}
}

//////////////////////////////////////////////////
bool Server::Reset(const std::size_t _runnerId)
{
if (_runnerId >= this->dataPtr->simRunners.size())
{
return false;
}
this->dataPtr->simRunners[_runnerId]->Reset(true, false, false);
return true;
}

//////////////////////////////////////////////////
void Server::Stop()
{
Expand Down
14 changes: 14 additions & 0 deletions src/SimulationRunner.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1661,3 +1661,17 @@ void SimulationRunner::CreateEntities(const sdf::World &_world)
// Store the initial state of the ECM;
this->initialEntityCompMgr.CopyFrom(this->entityCompMgr);
}

/////////////////////////////////////////////////
void SimulationRunner::Reset(const bool _all,
const bool _time, const bool _model)
{
WorldControl control;
std::lock_guard<std::mutex> lock(this->msgBufferMutex);
control.rewind = _all || _time;
if (_model)
{
gzwarn << "Model reset not supported" <<std::endl;
}
this->worldControls.push_back(control);
}
6 changes: 6 additions & 0 deletions src/SimulationRunner.hh
Original file line number Diff line number Diff line change
Expand Up @@ -369,6 +369,12 @@ namespace gz
/// \brief Set the next step to be blocking and paused.
public: void SetNextStepAsBlockingPaused(const bool value);

/// \brief Reset the current simulation runner
/// \param[in] all - Reset all parameters
/// \param[in] time - Reset the time
/// \param[in] model - Reset the model only [currently unsupported]
public: void Reset(const bool all, const bool time, const bool model);
Copy link
Contributor

Choose a reason for hiding this comment

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

Document parameters.

Copy link
Contributor Author

@arjo129 arjo129 Jan 8, 2025

Choose a reason for hiding this comment

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

I've left model reset in here because we have some scaffolding for it but, I'm not sure if I should leave it in.


/// \brief Updates the physics parameters of the simulation based on the
/// Physics component of the world, if any.
public: void UpdatePhysicsParams();
Expand Down
32 changes: 29 additions & 3 deletions src/TestFixture_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,8 @@ TEST_F(TestFixtureTest, Callbacks)
unsigned int preUpdates{0u};
unsigned int updates{0u};
unsigned int postUpdates{0u};
unsigned int resets{0u};

testFixture.
OnConfigure([&](const Entity &_entity,
const std::shared_ptr<const sdf::Element> &_sdf,
Expand All @@ -85,20 +87,33 @@ TEST_F(TestFixtureTest, Callbacks)
{
this->Updates(_info, _ecm);
preUpdates++;
EXPECT_EQ(preUpdates, _info.iterations);
if (resets == 0)
{
EXPECT_EQ(preUpdates, _info.iterations);
}
}).
OnUpdate([&](const UpdateInfo &_info, EntityComponentManager &_ecm)
{
this->Updates(_info, _ecm);
updates++;
EXPECT_EQ(updates, _info.iterations);
if (resets == 0)
{
EXPECT_EQ(updates, _info.iterations);
}
}).
OnPostUpdate([&](const UpdateInfo &_info,
const EntityComponentManager &_ecm)
{
this->Updates(_info, _ecm);
postUpdates++;
EXPECT_EQ(postUpdates, _info.iterations);
if (resets == 0)
{
EXPECT_EQ(postUpdates, _info.iterations);
}
}).
OnReset([&](const UpdateInfo &, EntityComponentManager &)
{
resets++;
}).
Finalize();

Expand All @@ -109,8 +124,19 @@ TEST_F(TestFixtureTest, Callbacks)
EXPECT_EQ(expectedIterations, preUpdates);
EXPECT_EQ(expectedIterations, updates);
EXPECT_EQ(expectedIterations, postUpdates);
EXPECT_EQ(0u, resets);

testFixture.Server()->ResetAll();

testFixture.Server()->Run(true, expectedIterations, false);
EXPECT_EQ(1u, configures);
EXPECT_EQ(expectedIterations * 2 - 1, preUpdates);
EXPECT_EQ(expectedIterations * 2 - 1, updates);
EXPECT_EQ(expectedIterations * 2 - 1, postUpdates);
EXPECT_EQ(1u, resets);
}


/////////////////////////////////////////////////
TEST_F(TestFixtureTest, LoadConfig)
{
Expand Down
Loading