Skip to content

Commit 699bf4b

Browse files
committed
Ensure logging is initialized only once
Signed-off-by: Ivan Santiago Paunovic <ivanpauno@ekumenlabs.com>
1 parent 2b04110 commit 699bf4b

File tree

2 files changed

+81
-1
lines changed

2 files changed

+81
-1
lines changed

rclpy/rclpy/context.py

Lines changed: 22 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,10 @@
2020
import weakref
2121

2222

23+
g_logging_configure_lock = threading.Lock()
24+
g_logging_ref_count = 0
25+
26+
2327
class Context:
2428
"""
2529
Encapsulates the lifecycle of init and shutdown.
@@ -35,22 +39,30 @@ def __init__(self):
3539
self._lock = threading.Lock()
3640
self._callbacks = []
3741
self._callbacks_lock = threading.Lock()
42+
self._logging_initialized = False
3843

3944
@property
4045
def handle(self):
4146
return self._handle
4247

43-
def init(self, args: Optional[List[str]] = None):
48+
def init(self, args: Optional[List[str]] = None, *, initialize_logging: bool = True):
4449
"""
4550
Initialize ROS communications for a given context.
4651
4752
:param args: List of command line arguments.
4853
"""
4954
# imported locally to avoid loading extensions on module import
5055
from rclpy.impl.implementation_singleton import rclpy_implementation
56+
global g_logging_ref_count
5157
with self._lock:
5258
rclpy_implementation.rclpy_init(
5359
args if args is not None else sys.argv, self._handle)
60+
if initialize_logging:
61+
self._logging_initialized = True
62+
with g_logging_configure_lock:
63+
g_logging_ref_count += 1
64+
if g_logging_ref_count == 1:
65+
rclpy_implementation.rclpy_logging_configure(self._handle)
5466

5567
def ok(self):
5668
"""Check if context hasn't been shut down."""
@@ -95,3 +107,12 @@ def on_shutdown(self, callback: Callable[[], None]):
95107
callback()
96108
else:
97109
self._callbacks.append(weakref.WeakMethod(callback, self._remove_callback))
110+
111+
def __del__(self):
112+
from rclpy.impl.implementation_singleton import rclpy_implementation
113+
global g_logging_ref_count
114+
if self._logging_initialized:
115+
with g_logging_configure_lock:
116+
g_logging_ref_count -= 1
117+
if g_logging_ref_count == 0:
118+
rclpy_implementation.rclpy_logging_fini()

rclpy/src/rclpy/_rclpy.c

Lines changed: 59 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
#include <rcl/error_handling.h>
2020
#include <rcl/expand_topic_name.h>
2121
#include <rcl/graph.h>
22+
#include <rcl/logging.h>
2223
#include <rcl/node.h>
2324
#include <rcl/publisher.h>
2425
#include <rcl/rcl.h>
@@ -618,6 +619,56 @@ rclpy_init(PyObject * Py_UNUSED(self), PyObject * args)
618619
Py_RETURN_NONE;
619620
}
620621

622+
/// Initialize rcl logging
623+
/**
624+
* Raises RuntimeError if rcl logging could not be initialized
625+
*/
626+
static PyObject *
627+
rclpy_logging_configure(PyObject * Py_UNUSED(self), PyObject * args)
628+
{
629+
// Expect one argument, a context.
630+
PyObject * pycontext;
631+
if (!PyArg_ParseTuple(args, "O", &pycontext)) {
632+
// Exception raised
633+
return NULL;
634+
}
635+
rcl_context_t * context = (rcl_context_t *)PyCapsule_GetPointer(pycontext, "rcl_context_t");
636+
if (!context) {
637+
return NULL;
638+
}
639+
rcl_allocator_t allocator = rcl_get_default_allocator();
640+
rcl_ret_t ret = rcl_logging_configure(
641+
&context->global_arguments,
642+
&allocator);
643+
if (RCL_RET_OK != ret) {
644+
PyErr_Format(
645+
RCLError,
646+
"Failed to initialize logging: %s", rcl_get_error_string().str);
647+
return NULL;
648+
}
649+
Py_RETURN_NONE;
650+
}
651+
652+
/// Finalize rcl logging
653+
/**
654+
* Raises RuntimeError if rcl logging could not be finalized
655+
*/
656+
static PyObject *
657+
rclpy_logging_fini(PyObject * Py_UNUSED(self), PyObject * Py_UNUSED(args))
658+
{
659+
rcl_ret_t ret = rcl_logging_fini();
660+
if (RCL_RET_OK != ret) {
661+
int stack_level = 1;
662+
PyErr_WarnFormat(
663+
PyExc_RuntimeWarning,
664+
stack_level,
665+
"Failed to fini logging: %s",
666+
rcl_get_error_string().str);
667+
return NULL;
668+
}
669+
Py_RETURN_NONE;
670+
}
671+
621672
/// PyCapsule destructor for node
622673
static void
623674
_rclpy_destroy_node(PyObject * pyentity)
@@ -5016,6 +5067,14 @@ static PyMethodDef rclpy_methods[] = {
50165067
"rclpy_init", rclpy_init, METH_VARARGS,
50175068
"Initialize RCL."
50185069
},
5070+
{
5071+
"rclpy_logging_configure", rclpy_logging_configure, METH_VARARGS,
5072+
"Initialize RCL logging."
5073+
},
5074+
{
5075+
"rclpy_logging_fini", rclpy_logging_fini, METH_NOARGS,
5076+
"Finalize RCL logging."
5077+
},
50195078
{
50205079
"rclpy_remove_ros_args", rclpy_remove_ros_args, METH_VARARGS,
50215080
"Remove ROS-specific arguments from argument vector."

0 commit comments

Comments
 (0)