def try_shutdown(*, context=None): """Shutdown rclpy if not already shutdown.""" global g_context_lock global g_default_context if context is None: # 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 init( *, args: Optional[List[str]] = None, context: Context = None, domain_id: Optional[int] = None, signal_handler_options: Optional[SignalHandlerOptions] = None, ) -> None: """ Initialize ROS communications for a given context. :param args: List of command line arguments. :param context: The context to initialize. If ``None``, then the default context is used (see :func:`.get_default_context`). :param domain_id: ROS domain id. :param signal_handler_options: Indicate which signal handlers to install. If `None`, SIGINT and SIGTERM will be installed when initializing the default context. """ context = get_default_context() if context is None else context if signal_handler_options is None: if context is None or context is get_default_context(): signal_handler_options = SignalHandlerOptions.ALL else: signal_handler_options = SignalHandlerOptions.NO install_signal_handlers(signal_handler_options) return context.init(args, domain_id=domain_id)
def init(*, args: Optional[List[str]] = None, context: Context = None) -> None: """ Initialize ROS communications for a given context. :param args: List of command line arguments. :param context: The context to initialize. If ``None``, then the default context is used (see :func:`.get_default_context`). """ context = get_default_context() if context is None else context return context.init(args)
def get_default_context(*, shutting_down=False): """Return the global default context singleton.""" global g_context_lock with g_context_lock: global g_default_context if g_default_context is None: g_default_context = Context() if shutting_down: old_context = g_default_context g_default_context = None return old_context return g_default_context
def test_on_shutdown_function(): context = Context() context.init() callback_called = False def on_shutdown(): nonlocal callback_called callback_called = True context.on_shutdown(on_shutdown) context.shutdown() assert callback_called
def test_on_shutdown_method(): context = Context() context.init() callback_called = False class SomeClass: def on_shutdown(self): nonlocal callback_called callback_called = True instance = SomeClass() context.on_shutdown(instance.on_shutdown) context.shutdown() assert callback_called
def test_sleep_for_invalid_context(): clock = Clock() with pytest.raises(NotInitializedException): clock.sleep_for(Duration(seconds=0.1), context=Context())
def non_default_context(): context = Context() context.init() yield context context.try_shutdown()