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

Every executor gets its own SIGINT guard condition #308

Merged
merged 25 commits into from
Apr 19, 2019
Merged
Show file tree
Hide file tree
Changes from 5 commits
Commits
Show all changes
25 commits
Select commit Hold shift + click to select a range
dda3de0
Every executor gets its own SIGINT guard condition
sloretz Apr 5, 2019
6690335
_sigint_gc robust to shutdown() called twice
sloretz Apr 8, 2019
d48b195
Remove redundant comments
sloretz Apr 8, 2019
506fb44
Split loop for readability
sloretz Apr 8, 2019
3538874
g_guard_conditions atomic variable
sloretz Apr 8, 2019
a2b1aaf
Use rclutils_atomics macros
sloretz Apr 8, 2019
3b250ab
Call original handler before losing reference to it
sloretz Apr 8, 2019
081c921
remove extra unnecessary assignment
sloretz Apr 8, 2019
6181a03
g_guard_conditions is a struct on windows
sloretz Apr 10, 2019
4802211
Rename action state transitions (#300)
jacobperron Apr 16, 2019
dcf1971
add missing error handling and cleanup (#315)
dirk-thomas Apr 17, 2019
28d9f55
Don't store sigint_gc address
sloretz Apr 19, 2019
3d25d7f
remove redundant conditional
sloretz Apr 19, 2019
f0a8dc6
Every executor gets its own SIGINT guard condition
sloretz Apr 5, 2019
dd17671
_sigint_gc robust to shutdown() called twice
sloretz Apr 8, 2019
4d706fe
Remove redundant comments
sloretz Apr 8, 2019
c8da2f1
Split loop for readability
sloretz Apr 8, 2019
83e1edb
g_guard_conditions atomic variable
sloretz Apr 8, 2019
215fb99
Use rclutils_atomics macros
sloretz Apr 8, 2019
63b2852
Call original handler before losing reference to it
sloretz Apr 8, 2019
f0dcb16
remove extra unnecessary assignment
sloretz Apr 8, 2019
571470c
g_guard_conditions is a struct on windows
sloretz Apr 10, 2019
b12ff20
Don't store sigint_gc address
sloretz Apr 19, 2019
ea96b9f
remove redundant conditional
sloretz Apr 19, 2019
5e92624
Merge branch 'sloretz/multiple_sigint_gcs' of https://github.com/ros2…
sloretz Apr 19, 2019
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
11 changes: 11 additions & 0 deletions rclpy/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -136,6 +136,17 @@ ament_target_dependencies(rclpy_logging
"rcutils"
)

# Signal handling library
add_library(
rclpy_signal_handler
SHARED src/rclpy/_rclpy_signal_handler.c
)
configure_python_c_extension_library(rclpy_signal_handler)
ament_target_dependencies(rclpy_signal_handler
"rcl"
"rcutils"
)

if(NOT WIN32)
ament_environment_hooks(
"${ament_cmake_package_templates_ENVIRONMENT_HOOK_LIBRARY_PATH}"
Expand Down
91 changes: 38 additions & 53 deletions rclpy/rclpy/executors.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@
from rclpy.guard_condition import GuardCondition
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
from rclpy.service import Service
from rclpy.signals import SignalHandlerGuardCondition
from rclpy.subscription import Subscription
from rclpy.task import Future
from rclpy.task import Task
Expand All @@ -45,13 +46,6 @@
from rclpy.waitable import NumberOfEntities
from rclpy.waitable import Waitable

# 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

# For documentation purposes
# TODO(jacobperron): Make all entities implement the 'Waitable' interface for better type checking
WaitableEntityType = TypeVar('WaitableEntityType')
Expand Down Expand Up @@ -166,6 +160,7 @@ def __init__(self, *, context: Context = None) -> None:
self._cb_iter = None
self._last_args = None
self._last_kwargs = None
self._sigint_gc = SignalHandlerGuardCondition(context)

@property
def context(self) -> Context:
Expand Down Expand Up @@ -213,6 +208,9 @@ def shutdown(self, timeout_sec: float = None) -> bool:
if self._guard_condition:
_rclpy.rclpy_destroy_entity(self._guard_condition)
self._guard_condition = None
if self._sigint_gc:
self._sigint_gc.destroy()
self._sigint_gc = None
self._cb_iter = None
self._last_args = None
self._last_kwargs = None
Expand All @@ -221,6 +219,8 @@ def shutdown(self, timeout_sec: float = None) -> bool:
def __del__(self):
if self._guard_condition is not None:
_rclpy.rclpy_destroy_entity(self._guard_condition)
if self._sigint_gc is not None:
self._sigint_gc.destroy()

def add_node(self, node: 'Node') -> bool:
"""
Expand Down Expand Up @@ -482,26 +482,23 @@ def _wait_for_ready_callbacks(
)
for waitable in waitables:
waitable.add_to_wait_set(wait_set)
(sigint_gc, sigint_gc_handle) = \
_rclpy.rclpy_get_sigint_guard_condition(self._context.handle)
try:
_rclpy.rclpy_wait_set_add_entity('guard_condition', wait_set, sigint_gc)
_rclpy.rclpy_wait_set_add_entity(
'guard_condition', wait_set, self._guard_condition)

# Wait for something to become ready
_rclpy.rclpy_wait(wait_set, timeout_nsec)
if self._is_shutdown:
raise ShutdownException()

# get ready entities
subs_ready = _rclpy.rclpy_get_ready_entities('subscription', wait_set)
guards_ready = _rclpy.rclpy_get_ready_entities('guard_condition', wait_set)
timers_ready = _rclpy.rclpy_get_ready_entities('timer', wait_set)
clients_ready = _rclpy.rclpy_get_ready_entities('client', wait_set)
services_ready = _rclpy.rclpy_get_ready_entities('service', wait_set)
finally:
_rclpy.rclpy_destroy_entity(sigint_gc)

sigint_gc = self._sigint_gc.guard_handle
_rclpy.rclpy_wait_set_add_entity('guard_condition', wait_set, sigint_gc)
_rclpy.rclpy_wait_set_add_entity(
'guard_condition', wait_set, self._guard_condition)

# Wait for something to become ready
_rclpy.rclpy_wait(wait_set, timeout_nsec)
if self._is_shutdown:
raise ShutdownException()

# get ready entities
subs_ready = _rclpy.rclpy_get_ready_entities('subscription', wait_set)
guards_ready = _rclpy.rclpy_get_ready_entities('guard_condition', wait_set)
timers_ready = _rclpy.rclpy_get_ready_entities('timer', wait_set)
clients_ready = _rclpy.rclpy_get_ready_entities('client', wait_set)
services_ready = _rclpy.rclpy_get_ready_entities('service', wait_set)

# Mark all guards as triggered before yielding since they're auto-taken
for gc in guards:
Expand Down Expand Up @@ -580,33 +577,21 @@ def wait_for_ready_callbacks(self, *args, **kwargs) -> Tuple[Task, WaitableEntit
.. Including the docstring for the hidden function for reference
.. automethod:: _wait_for_ready_callbacks
"""
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:
# 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
# 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
try:
return next(self._cb_iter)
except StopIteration:
# Generator ran out of work
self._cb_iter = None


class SingleThreadedExecutor(Executor):
Expand Down
1 change: 1 addition & 0 deletions rclpy/rclpy/impl/implementation_singleton.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,3 +31,4 @@
rclpy_implementation = _import('._rclpy')
rclpy_action_implementation = _import('._rclpy_action')
rclpy_logging_implementation = _import('._rclpy_logging')
rclpy_signal_handler_implementation = _import('._rclpy_signal_handler')
37 changes: 37 additions & 0 deletions rclpy/rclpy/signals.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
# Copyright 2019 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
from rclpy.impl.implementation_singleton import rclpy_signal_handler_implementation as _signals
from rclpy.utilities import get_default_context


class SignalHandlerGuardCondition:

def __init__(self, context=None):
if context is None:
context = get_default_context()
self.guard_handle, self.guard_pointer = _rclpy.rclpy_create_guard_condition(context.handle)
dirk-thomas marked this conversation as resolved.
Show resolved Hide resolved
_signals.rclpy_register_sigint_guard_condition(self.guard_handle)

def __del__(self):
self.destroy()

def destroy(self):
if self.guard_handle is None:
return
_signals.rclpy_unregister_sigint_guard_condition(self.guard_handle)
_rclpy.rclpy_destroy_entity(self.guard_handle)
self.guard_handle = None
self.guard_pointer = None
116 changes: 0 additions & 116 deletions rclpy/src/rclpy/_rclpy.c
Original file line number Diff line number Diff line change
Expand Up @@ -36,35 +36,8 @@
#include <rmw/validate_node_name.h>
#include <rosidl_generator_c/message_type_support_struct.h>

#include <signal.h>

#include "rclpy_common/common.h"

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)
{
(void) signo;
if (NULL != g_sigint_gc_handle) {
rcl_ret_t ret = rcl_trigger_guard_condition(g_sigint_gc_handle);
if (ret != RCL_RET_OK) {
PyErr_Format(PyExc_RuntimeError,
"Failed to trigger guard_condition: %s", rcl_get_error_string().str);
rcl_reset_error();
}
}
if (NULL != g_original_signal_handler) {
g_original_signal_handler(signo);
}
}

void
_rclpy_context_capsule_destructor(PyObject * capsule)
{
Expand Down Expand Up @@ -124,80 +97,6 @@ rclpy_create_context(PyObject * Py_UNUSED(self), PyObject * Py_UNUSED(args))
return PyCapsule_New(context, "rcl_context_t", _rclpy_context_capsule_destructor);
}

/// Create a sigint guard condition
/**
* A successful call will return a list with two elements:
*
* - a Capsule with the pointer of the created rcl_guard_condition_t * structure
* - an integer representing the memory address of the rcl_guard_condition_t
*
* Raises RuntimeError if initializing the guard condition fails
*
* \return a list with the capsule and memory location, or
* \return NULL on failure
*/
static PyObject *
rclpy_get_sigint_guard_condition(PyObject * Py_UNUSED(self), PyObject * args)
{
PyObject * pycontext;

if (!PyArg_ParseTuple(args, "O", &pycontext)) {
return NULL;
}

rcl_context_t * context = (rcl_context_t *)PyCapsule_GetPointer(pycontext, "rcl_context_t");
if (NULL == context) {
return NULL;
}

rcl_guard_condition_t * sigint_gc =
(rcl_guard_condition_t *)PyMem_Malloc(sizeof(rcl_guard_condition_t));
if (!sigint_gc) {
PyErr_Format(PyExc_MemoryError, "Failed to allocate memory for sigint guard condition");
return NULL;
}
*sigint_gc = rcl_get_zero_initialized_guard_condition();
rcl_guard_condition_options_t sigint_gc_options = rcl_guard_condition_get_default_options();

rcl_ret_t ret = rcl_guard_condition_init(sigint_gc, context, sigint_gc_options);
if (ret != RCL_RET_OK) {
PyErr_Format(PyExc_RuntimeError,
"Failed to create guard_condition: %s", rcl_get_error_string().str);
rcl_reset_error();
PyMem_Free(sigint_gc);
return NULL;
}

PyObject * pylist = PyList_New(2);
if (!pylist) {
ret = rcl_guard_condition_fini(sigint_gc);
PyMem_Free(sigint_gc);
return NULL;
}

PyObject * pysigint_gc = PyCapsule_New(sigint_gc, "rcl_guard_condition_t", NULL);
if (!pysigint_gc) {
ret = rcl_guard_condition_fini(sigint_gc);
PyMem_Free(sigint_gc);
Py_DECREF(pylist);
return NULL;
}

PyObject * pysigint_gc_impl_reference = PyLong_FromUnsignedLongLong((uint64_t)&sigint_gc->impl);
if (!pysigint_gc_impl_reference) {
ret = rcl_guard_condition_fini(sigint_gc);
PyMem_Free(sigint_gc);
Py_DECREF(pylist);
Py_DECREF(pysigint_gc);
return NULL;
}

g_sigint_gc_handle = sigint_gc;
PyList_SET_ITEM(pylist, 0, pysigint_gc);
PyList_SET_ITEM(pylist, 1, pysigint_gc_impl_reference);
return pylist;
}

/// Create a general purpose guard condition
/**
* A successful call will return a list with two elements:
Expand Down Expand Up @@ -604,9 +503,6 @@ rclpy_init(PyObject * Py_UNUSED(self), PyObject * args)
}
Py_DECREF(pyseqlist);

// Register our signal handler that will forward to the original one.
g_original_signal_handler = signal(SIGINT, catch_function);

if (PyErr_Occurred()) {
return NULL;
}
Expand Down Expand Up @@ -2405,9 +2301,6 @@ rclpy_destroy_entity(PyObject * Py_UNUSED(self), PyObject * args)
} else if (PyCapsule_IsValid(pyentity, "rcl_guard_condition_t")) {
rcl_guard_condition_t * guard_condition = (rcl_guard_condition_t *)PyCapsule_GetPointer(
pyentity, "rcl_guard_condition_t");
if (g_sigint_gc_handle == guard_condition) {
g_sigint_gc_handle = NULL;
}
ret = rcl_guard_condition_fini(guard_condition);
PyMem_Free(guard_condition);
} else {
Expand Down Expand Up @@ -3125,10 +3018,6 @@ rclpy_shutdown(PyObject * Py_UNUSED(self), PyObject * args)
return NULL;
}

// Restore the original signal handler.
signal(SIGINT, g_original_signal_handler);
g_original_signal_handler = NULL;

Py_RETURN_NONE;
}

Expand Down Expand Up @@ -4700,11 +4589,6 @@ static PyMethodDef rclpy_methods[] = {
"rclpy_create_timer", rclpy_create_timer, METH_VARARGS,
"Create a Timer."
},

{
"rclpy_get_sigint_guard_condition", rclpy_get_sigint_guard_condition, METH_VARARGS,
"Create a guard_condition triggered when sigint is received."
},
{
"rclpy_create_guard_condition", rclpy_create_guard_condition, METH_VARARGS,
"Create a general purpose guard_condition."
Expand Down
Loading