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

call the original signal handler when receiving SIGINT during wait #191

Merged
merged 5 commits into from
Jun 19, 2018
Merged
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
50 changes: 33 additions & 17 deletions rclpy/rclpy/executors.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,13 @@
from rclpy.utilities import ok
from rclpy.utilities import timeout_sec_to_nsec

# TODO(wjwwood): make _rclpy_wait(...) thread-safe
# Executor.spin_once() ends up calling _rclpy_wait(...), which right now is
# not thread-safe, no matter if different wait sets are used or not.
# See, for example, https://github.com/ros2/rclpy/issues/192
g_wait_set_spinning_lock = Lock()
g_wait_set_spinning = False


class _WaitSet:
"""Make sure the wait set gets destroyed when a generator exits."""
Expand Down Expand Up @@ -410,9 +417,6 @@ def _wait_for_ready_callbacks(self, timeout_sec=None, nodes=None):
clients_ready = _rclpy.rclpy_get_ready_entities('client', wait_set)
services_ready = _rclpy.rclpy_get_ready_entities('service', wait_set)

# Check sigint guard condition
if sigint_gc_handle in guards_ready:
raise KeyboardInterrupt
Copy link
Member Author

Choose a reason for hiding this comment

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

This case is no longer appropriate because the KeyboardInterrupt will be raised (if at all) from within _rclpy_wait() by the signal handler.

_rclpy.rclpy_destroy_entity(sigint_gc)

# Mark all guards as triggered before yielding any handlers since they're auto-taken
Expand Down Expand Up @@ -478,21 +482,33 @@ def wait_for_ready_callbacks(self, *args, **kwargs):

See :func:`Executor._wait_for_ready_callbacks` for documentation
"""
# if an old generator is done, this variable makes the loop get a new one before returning
got_generator = False
while not got_generator:
if self._cb_iter is None or self._last_args != args or self._last_kwargs != kwargs:
# Create a new generator
self._last_args = args
self._last_kwargs = kwargs
self._cb_iter = self._wait_for_ready_callbacks(*args, **kwargs)
got_generator = True
global g_wait_set_spinning_lock
global g_wait_set_spinning
with g_wait_set_spinning_lock:
if g_wait_set_spinning:
raise RuntimeError(
'Executor.wait_for_ready_callbacks() called concurrently in multiple threads')
g_wait_set_spinning = True

try:
return next(self._cb_iter)
except StopIteration:
# Generator ran out of work
self._cb_iter = None
try:
# if an old generator is done, this var makes the loop get a new one before returning
got_generator = False
while not got_generator:
if self._cb_iter is None or self._last_args != args or self._last_kwargs != kwargs:
# Create a new generator
self._last_args = args
self._last_kwargs = kwargs
self._cb_iter = self._wait_for_ready_callbacks(*args, **kwargs)
got_generator = True

try:
return next(self._cb_iter)
except StopIteration:
# Generator ran out of work
self._cb_iter = None
finally:
with g_wait_set_spinning_lock:
g_wait_set_spinning = False


class SingleThreadedExecutor(Executor):
Expand Down
19 changes: 12 additions & 7 deletions rclpy/src/rclpy/_rclpy.c
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,12 @@

static rcl_guard_condition_t * g_sigint_gc_handle;

#ifdef _WIN32
_crt_signal_t g_original_signal_handler = NULL;
#else
sig_t g_original_signal_handler = NULL;
#endif // _WIN32

/// Catch signals
static void catch_function(int signo)
{
Expand All @@ -43,6 +49,9 @@ static void catch_function(int signo)
"Failed to trigger guard_condition: %s", rcl_get_error_string_safe());
rcl_reset_error();
}
if (NULL != g_original_signal_handler) {
g_original_signal_handler(signo);
}
}

/// Create a sigint guard condition
Expand Down Expand Up @@ -2336,12 +2345,7 @@ rclpy_wait(PyObject * Py_UNUSED(self), PyObject * args)
if (!PyArg_ParseTuple(args, "O|K", &pywait_set, &timeout)) {
return NULL;
}
#ifdef _WIN32
_crt_signal_t
#else
sig_t
#endif // _WIN32
previous_handler = signal(SIGINT, catch_function);
g_original_signal_handler = signal(SIGINT, catch_function);
rcl_wait_set_t * wait_set = (rcl_wait_set_t *)PyCapsule_GetPointer(pywait_set, "rcl_wait_set_t");
if (!wait_set) {
return NULL;
Expand All @@ -2353,7 +2357,8 @@ rclpy_wait(PyObject * Py_UNUSED(self), PyObject * args)
ret = rcl_wait(wait_set, timeout);
Py_END_ALLOW_THREADS;

signal(SIGINT, previous_handler);
signal(SIGINT, g_original_signal_handler);
g_original_signal_handler = NULL;
if (ret != RCL_RET_OK && ret != RCL_RET_TIMEOUT) {
PyErr_Format(PyExc_RuntimeError,
"Failed to wait on wait set: %s", rcl_get_error_string_safe());
Expand Down