Skip to content

Commit

Permalink
1 to 2
Browse files Browse the repository at this point in the history
Signed-off-by: Ashton Larkin <[email protected]>
  • Loading branch information
adlarkin committed Nov 11, 2020
2 parents cf4fc4e + 6925457 commit 3fc15ae
Show file tree
Hide file tree
Showing 6 changed files with 75 additions and 14 deletions.
18 changes: 17 additions & 1 deletion Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -20,9 +20,25 @@

## Ignition Launch 1.x

### Ignition Launch 1.X.X (20XX-XX-XX)

### Ignition Launch 1.10.0 (2020-09-25)

1. Add PKGCONFIG information to ignition-tools ign_find_package
* [Pull Request 44](https://github.com/ignitionrobotics/ign-launch/pull/44)

1. Fix factory.ign launch file
* [Pull Request 55](https://github.com/ignitionrobotics/ign-launch/pull/55)

1. Use random name for manager semaphore
* [Pull Request 57](https://github.com/ignitionrobotics/ign-launch/pull/57)

1. Add support for specifying topics to record
* [Pull Request 54](https://github.com/ignitionrobotics/ign-launch/pull/54)

### Ignition Launch 1.9.0 (2020-08-13)

1. Added HTTP handling support to websocket server and a metrics HTTP endpoint
1. Added HTTP handling support to websocket server and a metrics HTTP endpoint
to monitor websocket server status.
* [Pull Request 49](https://github.com/ignitionrobotics/ign-launch/pull/49)

Expand Down
9 changes: 9 additions & 0 deletions plugins/gazebo_server/GazeboServer.cc
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,15 @@ bool GazeboServer::Load(const tinyxml2::XMLElement *_elem)
common::lowercase(str) == "true");
}

// Add topics to record, if present.
for (const tinyxml2::XMLElement *recordTopic =
elem->FirstChildElement("record_topic"); recordTopic;
recordTopic = recordTopic->NextSiblingElement("record_topic"))
{
std::string topic = recordTopic->GetText();
serverConfig.AddLogRecordTopic(topic);
}

const auto *resources = elem->FirstChildElement("resources");
if (resources)
{
Expand Down
8 changes: 6 additions & 2 deletions plugins/websocket_server/WebsocketServer.cc
Original file line number Diff line number Diff line change
Expand Up @@ -571,6 +571,7 @@ void WebsocketServer::OnConnect(int _socketId)
//////////////////////////////////////////////////
void WebsocketServer::OnDisconnect(int _socketId)
{
std::lock_guard<std::mutex> mainLock(this->subscriptionMutex);
// Skip invalid sockets
if (this->connections.find(_socketId) == this->connections.end())
return;
Expand Down Expand Up @@ -799,8 +800,11 @@ void WebsocketServer::OnWebsocketSubscribedMessage(
// Send the message
for (const int &socketId : iter->second)
{
this->QueueMessage(this->connections[socketId].get(),
msg.c_str(), msg.length());
if (this->connections.find(socketId) != this->connections.end())
{
this->QueueMessage(this->connections[socketId].get(),
msg.c_str(), msg.length());
}
}
}
}
Expand Down
1 change: 1 addition & 0 deletions src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@ target_link_libraries(${PROJECT_LIBRARY_TARGET_NAME}
TINYXML2::TINYXML2
PRIVATE
ignition-common${IGN_COMMON_MAJOR_VER}::ignition-common${IGN_COMMON_MAJOR_VER}
ignition-math${IGN_MATH_MAJOR_VER}::ignition-math${IGN_MATH_MAJOR_VER}
${BACKWARD_LIBRARIES}
)

Expand Down
51 changes: 41 additions & 10 deletions src/Manager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@
*
*/

#include "Manager.hh"

#include <fcntl.h>
#include <semaphore.h>
#include <signal.h>
Expand All @@ -24,31 +26,33 @@
#include <unistd.h>

#include <condition_variable>
#include <ctime>
#include <limits>
#include <list>
#include <mutex>
#include <numeric>
#include <queue>
#include <random>
#include <string>
#include <thread>
#include <unordered_set>
#include <utility>
#include <vector>

#include <ignition/common/Console.hh>
#include <ignition/common/SignalHandler.hh>
#include <ignition/common/SystemPaths.hh>
#include <ignition/math/Rand.hh>
#include <ignition/plugin/Loader.hh>

#include "ignition/launch/config.hh"
#include "ignition/launch/Plugin.hh"

#include "Manager.hh"
#include "vendor/backward.hpp"

using namespace ignition::launch;
using namespace std::chrono_literals;

static constexpr const char* kSemaphoreName = "/child_semaphore";

/// \brief A class to encapsulate an executable (program) to run.
class Executable
{
Expand Down Expand Up @@ -178,6 +182,9 @@ class ignition::launch::ManagerPrivate
/// \brief Semaphore to prevent restartThread from being a spinlock
private: sem_t *stoppedChildSem;

/// \brief Name of the semaphore created by stoppedChildSem.
private: std::string stoppedChildSemName;

/// \brief Thread containing the restart loop
private: std::thread restartThread;

Expand Down Expand Up @@ -294,18 +301,40 @@ ManagerPrivate::ManagerPrivate()
this->sigHandler->AddCallback(
std::bind(&ManagerPrivate::OnSigIntTerm, this, std::placeholders::_1));

{
// The semaphore we initialize in the next section needs a unique name, so
// we need to seed a random number generator with a quality random number.
// Especially time(0) itself is not a good seed as there may be multiple
// processes launched at the same time.
const auto time_seed = static_cast<size_t>(std::time(nullptr));
const auto pid_seed = std::hash<std::thread::id>()(
std::this_thread::get_id());
std::seed_seq seed_value{time_seed, pid_seed};
std::vector<size_t> seeds(1);
seed_value.generate(seeds.begin(), seeds.end());
math::Rand::Seed(seeds[0]);
}
const auto semRandomId = math::Rand::IntUniform(0,
std::numeric_limits<int32_t>::max());

// Initialize semaphore
this->stoppedChildSem = sem_open(kSemaphoreName, O_CREAT, 0644, 1);
if (this->stoppedChildSem == SEM_FAILED) {
ignerr << "Error initializing semaphore: " << strerror(errno) << std::endl;
this->stoppedChildSemName = std::string("ign-launch-") +
std::to_string(semRandomId);
this->stoppedChildSem = sem_open(this->stoppedChildSemName.c_str(), O_CREAT,
0644, 1);
if (this->stoppedChildSem == SEM_FAILED)
{
ignerr << "Error initializing semaphore " << this->stoppedChildSemName
<< ": " << strerror(errno) << std::endl;
}

// Register a signal handler to capture child process death events.
if (signal(SIGCHLD, ManagerPrivate::OnSigChild) == SIG_ERR)
ignerr << "signal(2) failed while setting up for SIGCHLD" << std::endl;

// Register backward signal handler for other signals
std::vector<int> signals = {
std::vector<int> signals =
{
SIGABRT, // Abort signal from abort(3)
SIGBUS, // Bus error (bad memory access)
SIGFPE, // Floating point exception
Expand All @@ -329,12 +358,14 @@ ManagerPrivate::~ManagerPrivate()
{
if (sem_close(this->stoppedChildSem) == -1)
{
ignerr << "Failed to close semaphore: " << strerror(errno) << std::endl;
ignerr << "Failed to close semaphore " << this->stoppedChildSemName
<< ": " << strerror(errno) << std::endl;
}

if (sem_unlink(kSemaphoreName) == -1)
if (sem_unlink(this->stoppedChildSemName.c_str()) == -1)
{
ignerr << "Failed to unlink semaphore: " << strerror(errno) << std::endl;
ignerr << "Failed to unlink semaphore " << this->stoppedChildSemName
<< ": " << strerror(errno) << std::endl;
}
}
}
Expand Down
2 changes: 1 addition & 1 deletion test/integration/plugins/bad_plugins.hh
Original file line number Diff line number Diff line change
Expand Up @@ -22,5 +22,5 @@ class SegfaultOnLoad : public ignition::launch::Plugin
{
public: SegfaultOnLoad();
public: virtual bool Load(
const tinyxml2::XMLElement * /*_elem*/) override final;
const tinyxml2::XMLElement * /*_elem*/) final;
};

0 comments on commit 3fc15ae

Please sign in to comment.