def execute(self, context: launch.LaunchContext) -> Optional[List[Action]]: """ Execute the action. Delegated to :meth:`launch.actions.ExecuteProcess.execute`. """ self._perform_substitutions( context) # ensure self.node_name is expanded if '<node_name_unspecified>' in self.node_name: raise RuntimeError( 'node_name unexpectedly incomplete for lifecycle node') # Create a subscription to monitor the state changes of the subprocess. self.__rclpy_subscription = context.locals.launch_ros_node.create_subscription( lifecycle_msgs.msg.TransitionEvent, '{}/transition_event'.format(self.node_name), functools.partial(self._on_transition_event, context), 10) # Create a service client to change state on demand. self.__rclpy_change_state_client = context.locals.launch_ros_node.create_client( lifecycle_msgs.srv.ChangeState, '{}/change_state'.format(self.node_name)) # Register an event handler to change states on a ChangeState lifecycle event. context.register_event_handler( launch.EventHandler( matcher=lambda event: isinstance(event, ChangeState), entities=[ launch.actions.OpaqueFunction( function=self._on_change_state_event) ], )) # Delegate execution to Node and ExecuteProcess. return super().execute(context)
def test_event_handler_handle_once(): """Test the option for handling events once for the EventHandler class.""" class MockEvent: ... mock_event = MockEvent() # Test handling multiple events with handle_once=False (default) eh_multiple = EventHandler(matcher=lambda event: True, handle_once=False) context_multiple = LaunchContext() context_multiple.register_event_handler(eh_multiple) eh_multiple.handle(mock_event, context_multiple) assert context_multiple.locals.event == mock_event # Attempt to handle a second event eh_multiple.handle(mock_event, context_multiple) # Test handling multiple events with handle_once=True eh_once = EventHandler(matcher=lambda event: True, handle_once=True) context_once = LaunchContext() context_once.register_event_handler(eh_once) eh_once.handle(mock_event, context_once) assert context_once.locals.event == mock_event # Attempt to handle a second event, this time expect ValueError because it is unregistered with pytest.raises(ValueError): eh_once.handle(mock_event, context_once)
def test_launch_context_register_event_handlers(): """Test registering of event handlers in LaunchContext class.""" lc = LaunchContext() class MockEventHandler: ... mock_event_handler = MockEventHandler() lc.register_event_handler(mock_event_handler) assert len(lc._event_handlers) == 1 assert lc._event_handlers[0] == mock_event_handler lc.unregister_event_handler(mock_event_handler) assert len(lc._event_handlers) == 0 with pytest.raises(ValueError): lc.unregister_event_handler(mock_event_handler)
def execute(self, context: LaunchContext) -> Optional[List[Action]]: """ Execute the ROS 2 sandbox inside Docker. This will start the Docker container and run each ROS 2 node from inside that container. There is no additional work required, so this function always returns None. """ context.register_event_handler( OnShutdown(on_shutdown=self.__on_shutdown)) self._completed_future = create_future(context.asyncio_loop) self._started_task = context.asyncio_loop.create_task( self._start_docker_nodes(context)) return None
def get_ros_adapter(context: launch.LaunchContext): """ Get the ROS adapter managed by the given launch context. If no adapter is found, one will be created. This function is reentrant but concurrent calls on the same `context` are not safe. """ if not hasattr(context.locals, 'ros_adapter'): ros_adapter = ROSAdapter() context.extend_globals({'ros_adapter': ros_adapter}) context.register_event_handler( launch.event_handlers.OnShutdown( on_shutdown=lambda *args, **kwargs: ros_adapter.shutdown())) return context.locals.ros_adapter
def _function(self, context: launch.LaunchContext): try: rclpy.init(args=context.argv) except RuntimeError as exc: if 'rcl_init called while already initialized' in str(exc): pass raise self.__launch_ros_node = rclpy.create_node('launch_ros') context.extend_globals({ 'ros_startup_action': self, 'launch_ros_node': self.__launch_ros_node }) context.register_event_handler( launch.event_handlers.OnShutdown(on_shutdown=self._shutdown, )) self.__rclpy_spin_thread = threading.Thread(target=self._run) self.__rclpy_spin_thread.start()
def execute(self, context: LaunchContext) -> Optional[List[Action]]: """ Execute the action. Delegated to :meth:`launch.actions.ExecuteProcess.execute`. """ actions = super().execute(context) if not self.__timeout: return actions self.__timer = TimerAction(period=self.__timeout, actions=[ OpaqueFunction( function=self._shutdown_process, kwargs={'send_sigint': True}) ]) on_process_exit_event = OnProcessExit(on_exit=self.__on_process_exit, target_action=self) context.register_event_handler(on_process_exit_event) if not actions: return [self.__timer] return actions.append(self.__timer)