From ad226136bd1675f886dcbc618044714c2edc8871 Mon Sep 17 00:00:00 2001 From: Ivan Santiago Paunovic Date: Wed, 18 Aug 2021 11:06:27 -0300 Subject: [PATCH] Call Context._logging_fini() in Context.try_shutdown() (#800) Signed-off-by: Ivan Santiago Paunovic --- rclpy/rclpy/context.py | 41 ++++++++++++++++++++--------------------- 1 file changed, 20 insertions(+), 21 deletions(-) diff --git a/rclpy/rclpy/context.py b/rclpy/rclpy/context.py index 39c195c93..4794af154 100644 --- a/rclpy/rclpy/context.py +++ b/rclpy/rclpy/context.py @@ -36,7 +36,6 @@ class Context: def __init__(self): self._lock = threading.Lock() self._callbacks = [] - self._callbacks_lock = threading.Lock() self._logging_initialized = False self.__context = None @@ -89,12 +88,11 @@ def ok(self): return self.__context.ok() def _call_on_shutdown_callbacks(self): - with self._callbacks_lock: - for weak_method in self._callbacks: - callback = weak_method() - if callback is not None: - callback() - self._callbacks = [] + for weak_method in self._callbacks: + callback = weak_method() + if callback is not None: + callback() + self._callbacks = [] def shutdown(self): """Shutdown this context.""" @@ -102,8 +100,8 @@ def shutdown(self): raise RuntimeError('Context must be initialized before it can be shutdown') with self.__context, self._lock: self.__context.shutdown() - self._call_on_shutdown_callbacks() - self._logging_fini() + self._call_on_shutdown_callbacks() + self._logging_fini() def try_shutdown(self): """Shutdown this context, if not already shutdown.""" @@ -113,6 +111,7 @@ def try_shutdown(self): if self.__context.ok(): self.__context.shutdown() self._call_on_shutdown_callbacks() + self._logging_fini() def _remove_callback(self, weak_method): self._callbacks.remove(weak_method) @@ -121,25 +120,25 @@ def on_shutdown(self, callback: Callable[[], None]): """Add a callback to be called on shutdown.""" if not callable(callback): raise TypeError('callback should be a callable, got {}', type(callback)) - with self._callbacks_lock: - if not self.ok(): + with self.__context, self._lock: + if not self.__context.ok(): callback() else: self._callbacks.append(weakref.WeakMethod(callback, self._remove_callback)) def _logging_fini(self): + # This function must be called with self._lock held. from rclpy.impl.implementation_singleton import rclpy_implementation global g_logging_ref_count - with self._lock: - if self._logging_initialized: - with g_logging_configure_lock: - g_logging_ref_count -= 1 - if g_logging_ref_count == 0: - rclpy_implementation.rclpy_logging_fini() - if g_logging_ref_count < 0: - raise RuntimeError( - 'Unexpected error: logger ref count should never be lower that zero') - self._logging_initialized = False + if self._logging_initialized: + with g_logging_configure_lock: + g_logging_ref_count -= 1 + if g_logging_ref_count == 0: + rclpy_implementation.rclpy_logging_fini() + if g_logging_ref_count < 0: + raise RuntimeError( + 'Unexpected error: logger ref count should never be lower that zero') + self._logging_initialized = False def get_domain_id(self): """Get domain id of context."""