diff --git a/rclpy/rclpy/__init__.py b/rclpy/rclpy/__init__.py index 3068f2702..cea1f9163 100644 --- a/rclpy/rclpy/__init__.py +++ b/rclpy/rclpy/__init__.py @@ -100,6 +100,13 @@ def get_global_executor() -> 'Executor': # imported locally to avoid loading extensions on module import from rclpy.executors import SingleThreadedExecutor __executor = SingleThreadedExecutor() + context = get_default_context() + + def reset_executor(): + global __executor + __executor.shutdown() + __executor = None + context.on_shutdown(reset_executor) return __executor @@ -116,10 +123,6 @@ def shutdown(*, context: Context = None, uninstall_handlers: Optional[bool] = No If `True`, signal handlers will be uninstalled. If not, signal handlers won't be uninstalled. """ - global __executor - if __executor is not None: - __executor.shutdown() - __executor = None _shutdown(context=context) if ( uninstall_handlers or ( diff --git a/rclpy/rclpy/context.py b/rclpy/rclpy/context.py index 5471751bc..4e86d6950 100644 --- a/rclpy/rclpy/context.py +++ b/rclpy/rclpy/context.py @@ -127,7 +127,7 @@ def on_shutdown(self, callback: Callable[[], None]): if ismethod(callback): self._callbacks.append(weakref.WeakMethod(callback, self._remove_callback)) else: - self._callbacks.append(weakref.ref(callback, self._remove_callback)) + self._callbacks.append(callback) def _logging_fini(self): # This function must be called with self._lock held. diff --git a/rclpy/rclpy/utilities.py b/rclpy/rclpy/utilities.py index 96aad026d..ee7c86806 100644 --- a/rclpy/rclpy/utilities.py +++ b/rclpy/rclpy/utilities.py @@ -60,9 +60,19 @@ def shutdown(*, context=None): def try_shutdown(*, context=None): """Shutdown rclpy if not already shutdown.""" + global g_context_lock + global g_default_context if context is None: - context = get_default_context() - return context.try_shutdown() + # Replace the default context with a new one if shutdown was successful + # or if the context was already shutdown. + with g_context_lock: + if g_default_context is None: + g_default_context = Context() + g_default_context.try_shutdown() + if not g_default_context.ok(): + g_default_context = None + else: + return context.try_shutdown() def get_rmw_implementation_identifier():