Skip to content

Commit

Permalink
Use self-pipe trick to implement signal handlers
Browse files Browse the repository at this point in the history
This allows the rest of the Gazebo codebase to use callbacks that can
use non async-signal-safe functions

Signed-off-by: Addisu Z. Taddese <addisu@openrobotics.org>
  • Loading branch information
azeey committed Jul 26, 2024
1 parent 3930407 commit 049d75c
Showing 1 changed file with 95 additions and 3 deletions.
98 changes: 95 additions & 3 deletions src/SignalHandler.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,11 @@
// comments when upgrading to gz-cmake's "make codecheck"
#include "gz/common/SignalHandler.hh" // NOLINT(*)
#include <atomic>
#include <cstring>
#include <csignal> // NOLINT(*)
#include <functional> // NOLINT(*)
#include <fcntl.h>
#include <unistd.h>
#include <map> // NOLINT(*)
#include <mutex> // NOLINT(*)
#include <utility> // NOLINT(*)
Expand All @@ -31,13 +34,52 @@ using namespace gz;
using namespace common;

// A wrapper for the sigaction sa_handler.
// TODO(azeey) We should avoid using objects with non-trivial destructors as globals.
GZ_COMMON_VISIBLE std::map<int, std::function<void(int)>> gOnSignalWrappers;
std::mutex gWrapperMutex;

namespace
{

class SelfPipe
{
public:
static int pipeFd[2];

public:
static void Initialize();

public:
~SelfPipe();

private:
SelfPipe();

private:
void CheckPipe();

private:
std::thread checkPipeThread;

private:
std::atomic<bool> running{false};
};

int SelfPipe::pipeFd[2];

void onSignalTopHalf(int _value)
{
auto valueByte = static_cast<std::uint8_t>(_value);
if (write(SelfPipe::pipeFd[1], &valueByte, 1) == -1)
{
// TODO (azeey) Not clear what to do here.
}
}

/////////////////////////////////////////////////
/// \brief Callback to execute when a signal is received.
/// \param[in] _value Signal number.
void onSignal(int _value)
void onSignalBottomHalf(int _value)
{
std::lock_guard<std::mutex> lock(gWrapperMutex);
// Send the signal to each wrapper
Expand All @@ -47,6 +89,55 @@ void onSignal(int _value)
}
}

SelfPipe::SelfPipe()
{
if (pipe(this->pipeFd))
{
gzerr << "Unable to create pipe\n";
}

int flags = fcntl(this->pipeFd[1], F_GETFL);
fcntl(this->pipeFd[1], F_SETFL, flags | O_NONBLOCK);
// TODO(azeey) Handle errors
this->running = true;
std::cout << "Initialized self pipe " << running << std::endl;
this->checkPipeThread = std::thread(&SelfPipe::CheckPipe, this);
}

SelfPipe::~SelfPipe()
{
this->running = false;
onSignalTopHalf(127);
this->checkPipeThread.join();
}
void SelfPipe::Initialize()
{
// We actually need this object to be destructed in order to join the thread,
// so we can't use gz::utils::NeverDestroyed here.
static SelfPipe selfPipe;
}

void SelfPipe::CheckPipe()
{
while (this->running)
{
std::uint8_t signal;
if (read(SelfPipe::pipeFd[0], &signal, 1) != -1)
{
if (this->running)
{
onSignalBottomHalf(signal);
}
}
else
{
gzerr << errno << " " << std::strerror(errno) << std::endl;
}
}
}

} // namespace

/////////////////////////////////////////////////
class common::SignalHandlerPrivate
{
Expand Down Expand Up @@ -74,14 +165,15 @@ SignalHandler::SignalHandler()
static int counter = 0;
std::lock_guard<std::mutex> lock(gWrapperMutex);

if (std::signal(SIGINT, onSignal) == SIG_ERR)
SelfPipe::Initialize();
if (std::signal(SIGINT, onSignalTopHalf) == SIG_ERR)
{
gzerr << "Unable to catch SIGINT.\n"
<< " Please visit http://community.gazebosim.org for help.\n";
return;
}

if (std::signal(SIGTERM, onSignal) == SIG_ERR)
if (std::signal(SIGTERM, onSignalTopHalf) == SIG_ERR)
{
gzerr << "Unable to catch SIGTERM.\n"
<< " Please visit http://community.gazebosim.org for help.\n";
Expand Down

0 comments on commit 049d75c

Please sign in to comment.