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

Restore log playback #2590

Closed
wants to merge 3 commits into from
Closed
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
1 change: 1 addition & 0 deletions src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -222,6 +222,7 @@ target_link_libraries(${PROJECT_LIBRARY_TARGET_NAME}
gz-rendering${GZ_RENDERING_VER}::core
gz-transport${GZ_TRANSPORT_VER}::gz-transport${GZ_TRANSPORT_VER}
gz-transport${GZ_TRANSPORT_VER}::parameters
gz-transport${GZ_TRANSPORT_VER}::log
sdformat${SDF_VER}::sdformat${SDF_VER}
protobuf::libprotobuf
PRIVATE
Expand Down
107 changes: 103 additions & 4 deletions src/Server.cc
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,11 @@
#include <gz/common/SystemPaths.hh>
#include <gz/fuel_tools/Interface.hh>
#include <gz/fuel_tools/ClientConfig.hh>
#include <gz/transport/log/Log.hh>

#include "gz/sim/components/World.hh"
#include "gz/sim/components/Name.hh"

#include <sdf/Root.hh>
#include <sdf/Error.hh>
#include <sdf/ParserConfig.hh>
Expand Down Expand Up @@ -58,6 +63,90 @@ struct DefaultWorld
}
};


namespace {
// A slow and ugly hack to restore Log playback
std::optional<std::string>
WorldFromLog(std::string logPath)
{
if (common::isFile(logPath))
{
// TODO(arjo): Restore Zip-file
return std::nullopt;
}

std::string dbPath = common::joinPaths(logPath,
"state.tlog");
gzmsg << "Loading log file [" + dbPath + "]\n";
if (!common::exists(dbPath))
{
gzerr << "Log path invalid. File [" << dbPath << "] "
<< "does not exist. Nothing to play.\n";
return std::nullopt;
}

auto log = std::make_unique<transport::log::Log>();
if (!log->Open(dbPath))
{
gzerr << "Failed to open log file [" << dbPath << "]" << std::endl;
return std::nullopt;
}

auto batch = log->QueryMessages();
auto iter = batch.begin();

if (iter == batch.end())
{
gzerr << "No messages found in log file [" << dbPath << "]" << std::endl;
return std::nullopt;
}

EntityComponentManager tempEcm;
// Look for the first SerializedState message and use it to set the initial
// state of the world. Messages received before this are ignored.
for (; iter != batch.end(); ++iter)
{
auto msgType = iter->Type();
if (msgType == "gz.msgs.SerializedState")
{
msgs::SerializedState msg;
msg.ParseFromString(iter->Data());
tempEcm.SetState(msg);
break;
}
else if (msgType == "gz.msgs.SerializedStateMap")
{
msgs::SerializedStateMap msg;
msg.ParseFromString(iter->Data());
tempEcm.SetState(msg);
break;
}
}
auto worldEntity = tempEcm.EntityByComponents(components::World());
if (kNullEntity == worldEntity)
{
// Seems like levels logs can start without a world component
gzwarn << "Log file has no initial world component.\n";
return DefaultWorld::World();
}

auto name = tempEcm.ComponentData<components::Name>(worldEntity);
if (!name.has_value())
{
gzwarn << "Log file world has no name component.\n";
return DefaultWorld::World();
}

std::stringstream worldTemplate;
worldTemplate << "<sdf version='1.6'>"
<< "<world name='"<< name.value() <<"'>"
<< "</world>"
<< "</sdf>";
return worldTemplate.str();
}

}

/////////////////////////////////////////////////
Server::Server(const ServerConfig &_config)
: dataPtr(new ServerPrivate)
Expand Down Expand Up @@ -190,10 +279,20 @@ Server::Server(const ServerConfig &_config)
case ServerConfig::SourceType::kNone:
default:
{
gzmsg << "Loading default world.\n";
// Load an empty world.
/// \todo(nkoenig) Add a "AddWorld" function to sdf::Root.
errors = this->dataPtr->sdfRoot.LoadSdfString(DefaultWorld::World());
if (_config.LogPlaybackPath() == "")
{
// Load an empty world.
/// \todo(nkoenig) Add a "AddWorld" function to sdf::Root.
errors = this->dataPtr->sdfRoot.LoadSdfString(DefaultWorld::World());
}
else
{
auto world = WorldFromLog(_config.LogPlaybackPath());
if (world.has_value())
this->dataPtr->sdfRoot.LoadSdfString(world.value());
else
return;
}
break;
}
}
Expand Down
2 changes: 1 addition & 1 deletion test/integration/log_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -904,7 +904,7 @@ TEST_F(LogSystemTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(LogControl))
msgs::Boolean res;
bool result{false};
unsigned int timeout = 1000;
std::string service{"/world/default/playback/control"};
std::string service{"/world/shapes/playback/control"};
for (auto i : secs)
{
req.mutable_seek()->set_sec(i);
Expand Down
Loading