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

Combined server gui #417

Closed
wants to merge 7 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
44 changes: 15 additions & 29 deletions src/cmd/cmdgazebo.rb.in
Original file line number Diff line number Diff line change
Expand Up @@ -418,6 +418,14 @@ class Cmd
# Import the runGui function
Importer.extern 'int runGui(const char *)'

# Import the runCombined function
Importer.extern 'int runCombined(const char *, int, int, float, int,
const char *, int, int, const char *,
int, int, int, const char *, const char *,
const char *, const char *, const char *,
const char *, const char *)'


# If playback is specified, and the user has not specified a
# custom gui config, set the gui config to load the playback
# gui config
Expand All @@ -429,45 +437,22 @@ class Cmd
# and gui.
if options['server'] == 0 && options['gui'] == 0

serverPid = Process.fork do
ENV['RMT_PORT'] = '1500'
Process.setpgid(0, 0)
Process.setproctitle('ign gazebo server')
Importer.runServer(parsed, options['iterations'], options['run'],
ENV['RMT_PORT'] = '1500'
Process.setproctitle('ign gazebo')
Importer.runCombined(parsed, options['iterations'], options['run'],
options['hz'], options['levels'], options['network_role'],
options['network_secondaries'], options['record'],
options['record-path'], options['record-resources'],
options['log-overwrite'], options['log-compress'],
options['playback'], options['physics_engine'],
options['render_engine_server'], options['render_engine_gui'],
options['file'], options['record-topics'].join(':'))
end

guiPid = Process.fork do
ENV['RMT_PORT'] = '1501'
Process.setpgid(0, 0)
Process.setproctitle('ign gazebo gui')
Importer.runGui(options['gui_config'])
end

Signal.trap("INT") {
self.killProcess(guiPid, "Ignition Gazebo GUI", 5.0)
self.killProcess(serverPid, "Ignition Gazebo Server", 5.0)
return 1
}

# Wait for a child process to end
pid, status = Process.wait2

if pid == serverPid
self.killProcess(guiPid, "Ignition Gazebo GUI", 5.0)
else
self.killProcess(serverPid, "Ignition Gazebo Server", 5.0)
end
options['file'], options['record-topics'].join(':'),
options['gui_config'])

# If the -s option was specified, then run only the server
elsif options['server'] == 1
ENV['RMT_PORT'] = '1500'
Process.setproctitle('ign gazebo -s')
Importer.runServer(parsed, options['iterations'], options['run'],
options['hz'], options['levels'], options['network_role'],
options['network_secondaries'], options['record'],
Expand All @@ -479,6 +464,7 @@ class Cmd
# Otherwise run the gui
else options['gui']
ENV['RMT_PORT'] = '1501'
Process.setproctitle('ign gazebo -g')
Importer.runGui(options['gui_config'])
end
rescue
Expand Down
18 changes: 16 additions & 2 deletions src/gui/GuiRunner.cc
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,8 @@
using namespace ignition;
using namespace gazebo;

std::thread *gRequestThread = nullptr;

/////////////////////////////////////////////////
GuiRunner::GuiRunner(const std::string &_worldName)
{
Expand All @@ -50,15 +52,27 @@ GuiRunner::GuiRunner(const std::string &_worldName)
igndbg << "Requesting initial state from [" << this->stateTopic << "]..."
<< std::endl;

this->RequestState();
// \todo: HACK warning. This thread should be removed when the deadlock
// in ignition transport is resolved. See also the todo in RequestState.
gRequestThread = new std::thread([&](){this->RequestState();});
}

/////////////////////////////////////////////////
GuiRunner::~GuiRunner() = default;
GuiRunner::~GuiRunner()
{
if (gRequestThread)
{
gRequestThread->join();
delete gRequestThread;
}
}

/////////////////////////////////////////////////
void GuiRunner::RequestState()
{
// \todo: HACK warning. This sleep is here to prevent a deadlock in
// ignition-transport.
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
this->node.Request(this->stateTopic, &GuiRunner::OnStateService, this);
}

Expand Down
114 changes: 85 additions & 29 deletions src/ign.cc
Original file line number Diff line number Diff line change
Expand Up @@ -109,18 +109,17 @@ extern "C" IGNITION_GAZEBO_VISIBLE const char *findFuelResource(
}

//////////////////////////////////////////////////
extern "C" IGNITION_GAZEBO_VISIBLE int runServer(const char *_sdfString,
int _iterations, int _run, float _hz, int _levels, const char *_networkRole,
int createServerConfig(ignition::gazebo::ServerConfig &_serverConfig,
const char *_sdfString,
float _hz, int _levels, const char *_networkRole,
int _networkSecondaries, int _record, const char *_recordPath,
int _recordResources, int _logOverwrite, int _logCompress,
const char *_playback, const char *_physicsEngine,
const char *_renderEngineServer, const char *_renderEngineGui,
const char *_file, const char *_recordTopics)
{
ignition::gazebo::ServerConfig serverConfig;

// Path for logs
std::string recordPathMod = serverConfig.LogRecordPath();
std::string recordPathMod = _serverConfig.LogRecordPath();

// Path for compressed log, used to check for duplicates
std::string cmpPath = std::string(recordPathMod);
Expand All @@ -142,8 +141,8 @@ extern "C" IGNITION_GAZEBO_VISIBLE int runServer(const char *_sdfString,
return -1;
}

serverConfig.SetUseLogRecord(true);
serverConfig.SetLogRecordResources(_recordResources);
_serverConfig.SetUseLogRecord(true);
_serverConfig.SetLogRecordResources(_recordResources);

// If a record path is specified
if (_recordPath != nullptr && std::strlen(_recordPath) > 0)
Expand Down Expand Up @@ -252,8 +251,8 @@ extern "C" IGNITION_GAZEBO_VISIBLE int runServer(const char *_sdfString,
// console logs and LogRecord recordings to common::ignLogDirectory().
// In Blueprint and Citadel, LogRecord will record to <path> if no
// --record-path is specified on command line.
serverConfig.SetLogRecordPath(recordPathMod);
serverConfig.SetLogIgnoreSdfPath(true);
_serverConfig.SetLogRecordPath(recordPathMod);
_serverConfig.SetLogIgnoreSdfPath(true);
}
// Empty record path specified. Use default.
else
Expand All @@ -263,24 +262,24 @@ extern "C" IGNITION_GAZEBO_VISIBLE int runServer(const char *_sdfString,
ignmsg << "Recording states to default path [" << recordPathMod << "]"
<< std::endl;

serverConfig.SetLogRecordPath(recordPathMod);
_serverConfig.SetLogRecordPath(recordPathMod);
}

std::vector<std::string> topics = ignition::common::split(
_recordTopics, ":");
for (const std::string &topic : topics)
{
serverConfig.AddLogRecordTopic(topic);
_serverConfig.AddLogRecordTopic(topic);
}
}
else
{
ignLogInit(serverConfig.LogRecordPath(), "server_console.log");
ignLogInit(_serverConfig.LogRecordPath(), "server_console.log");
}

if (_logCompress > 0)
{
serverConfig.SetLogRecordCompressPath(cmpPath);
_serverConfig.SetLogRecordCompressPath(cmpPath);
}

ignmsg << "Ignition Gazebo Server v" << IGNITION_GAZEBO_VERSION_FULL
Expand All @@ -289,31 +288,31 @@ extern "C" IGNITION_GAZEBO_VISIBLE int runServer(const char *_sdfString,
// Set the SDF string to user
if (_sdfString != nullptr && std::strlen(_sdfString) > 0)
{
if (!serverConfig.SetSdfString(_sdfString))
if (!_serverConfig.SetSdfString(_sdfString))
{
ignerr << "Failed to set SDF string [" << _sdfString << "]" << std::endl;
return -1;
}
}
serverConfig.SetSdfFile(_file);
_serverConfig.SetSdfFile(_file);

// Set the update rate.
if (_hz > 0.0)
serverConfig.SetUpdateRate(_hz);
_serverConfig.SetUpdateRate(_hz);

// Set whether levels should be used.
if (_levels > 0)
{
ignmsg << "Using the level system\n";
serverConfig.SetUseLevels(true);
_serverConfig.SetUseLevels(true);
}

if (_networkRole && std::strlen(_networkRole) > 0)
{
ignmsg << "Using the distributed simulation and levels systems\n";
serverConfig.SetNetworkRole(_networkRole);
serverConfig.SetNetworkSecondaries(_networkSecondaries);
serverConfig.SetUseLevels(true);
_serverConfig.SetNetworkRole(_networkRole);
_serverConfig.SetNetworkSecondaries(_networkSecondaries);
_serverConfig.SetUseLevels(true);
}

if (_playback != nullptr && std::strlen(_playback) > 0)
Expand All @@ -327,34 +326,58 @@ extern "C" IGNITION_GAZEBO_VISIBLE int runServer(const char *_sdfString,
else
{
ignmsg << "Playing back states" << _playback << std::endl;
serverConfig.SetLogPlaybackPath(ignition::common::absPath(
_serverConfig.SetLogPlaybackPath(ignition::common::absPath(
std::string(_playback)));
}
}

if (_physicsEngine != nullptr && std::strlen(_physicsEngine) > 0)
{
serverConfig.SetPhysicsEngine(_physicsEngine);
_serverConfig.SetPhysicsEngine(_physicsEngine);
}

if (_renderEngineServer != nullptr && std::strlen(_renderEngineServer) > 0)
{
serverConfig.SetRenderEngineServer(_renderEngineServer);
_serverConfig.SetRenderEngineServer(_renderEngineServer);
}

if (_renderEngineGui != nullptr && std::strlen(_renderEngineGui) > 0)
{
serverConfig.SetRenderEngineGui(_renderEngineGui);
_serverConfig.SetRenderEngineGui(_renderEngineGui);
}

return 0;
}

//////////////////////////////////////////////////
extern "C" IGNITION_GAZEBO_VISIBLE int runServer(const char *_sdfString,
int _iterations, int _run, float _hz, int _levels, const char *_networkRole,
int _networkSecondaries, int _record, const char *_recordPath,
int _recordResources, int _logOverwrite, int _logCompress,
const char *_playback, const char *_physicsEngine,
const char *_renderEngineServer, const char *_renderEngineGui,
const char *_file, const char *_recordTopics)
{
// Create the Gazebo server
ignition::gazebo::Server server(serverConfig);
ignition::gazebo::ServerConfig serverConfig;

// Run the server
server.Run(true, _iterations, _run == 0);
if (createServerConfig(serverConfig,
_sdfString, _hz, _levels, _networkRole,
_networkSecondaries, _record, _recordPath,
_recordResources, _logOverwrite, _logCompress,
_playback, _physicsEngine, _renderEngineServer,
_renderEngineGui, _file, _recordTopics) == 0)
{
ignition::gazebo::Server server(serverConfig);
// Run the server
server.Run(true, _iterations, _run == 0);

igndbg << "Shutting down ign-gazebo-server" << std::endl;
return 0;
igndbg << "Shutting down ign-gazebo-server" << std::endl;
return 0;
}

ignerr << "Unable to create server config" << std::endl;
return -1;
}

//////////////////////////////////////////////////
Expand All @@ -373,3 +396,36 @@ extern "C" IGNITION_GAZEBO_VISIBLE int runGui(const char *_guiConfig)
char *argv = const_cast<char *>("ign-gazebo-gui");
return ignition::gazebo::gui::runGui(argc, &argv, _guiConfig);
}

//////////////////////////////////////////////////
extern "C" IGNITION_GAZEBO_VISIBLE int runCombined(const char *_sdfString,
int _iterations, int _run, float _hz, int _levels, const char *_networkRole,
int _networkSecondaries, int _record, const char *_recordPath,
int _recordResources, int _logOverwrite, int _logCompress,
const char *_playback, const char *_physicsEngine,
const char *_renderEngineServer, const char *_renderEngineGui,
const char *_file, const char *_recordTopics, const char *_guiConfig)
{
ignition::gazebo::ServerConfig serverConfig;

if (createServerConfig(serverConfig,
_sdfString, _hz, _levels, _networkRole,
_networkSecondaries, _record, _recordPath,
_recordResources, _logOverwrite, _logCompress,
_playback, _physicsEngine, _renderEngineServer,
_renderEngineGui, _file, _recordTopics) == 0)
{
// Create the Gazebo server
ignition::gazebo::Server server(serverConfig);

// Run the server
server.Run(false, _iterations, _run == 0);

// Run the gui
return runGui(_guiConfig);
}

ignerr << "Unable to create server config\n";

return -1;
}
30 changes: 30 additions & 0 deletions src/ign.hh
Original file line number Diff line number Diff line change
Expand Up @@ -76,4 +76,34 @@ extern "C" IGNITION_GAZEBO_VISIBLE int runGui(const char *_guiConfig);
extern "C" IGNITION_GAZEBO_VISIBLE const char *findFuelResource(
char *_pathToResource);

/// \brief External hook to run simulation server and GUI.
/// \param[in] _sdfString SDF file to run, as a string.
/// \param[in] _iterations --iterations option
/// \param[in] _run -r option
/// \param[in] _hz -z option
/// \param[in] _levels --levels option
/// \param[in] _networkRole --network-role option
/// \param[in] _networkSecondaries --network-secondaries option
/// \param[in] _record --record option
/// \param[in] _recordPath --record-path option
/// \param[in] _recordResources --record-resources option
/// \param[in] _logOverwrite --log-overwrite option
/// \param[in] _logCompress --log-compress option
/// \param[in] _playback --playback option
/// \param[in] _physicsEngine --physics-engine option
/// \param[in] _renderEngineServer --render-engine-server option
/// \param[in] _renderEngineGui --render-engine-gui option
/// \param[in] _file Path to file being loaded
/// \param[in] _recordTopics Colon separated list of topics to record. Leave
/// null to record the default topics.
/// \param[in] _guiConfig Path to Ignition GUI configuration file.
/// \return 0 if successful, 1 if not.
extern "C" IGNITION_GAZEBO_VISIBLE int runCombined(const char *_sdfString,
int _iterations, int _run, float _hz, int _levels, const char *_networkRole,
int _networkSecondaries, int _record, const char *_recordPath,
int _recordResources, int _logOverwrite, int _logCompress,
const char *_playback, const char *_physicsEngine,
const char *_renderEngineServer, const char *_renderEngineGui,
const char *_file, const char *_recordTopics, const char *_guiConfig);

#endif