def generate_preamble(self): return [launch.actions.IncludeLaunchDescription( launch_description_source=launch.LaunchDescriptionSource( launch_description=launch_ros.get_default_launch_description( rclpy_context=self._rclpy_context, ) ) )]
def generate_preamble(self): import launch_ros # Import on first use to avoid races at module level return [ launch.actions.IncludeLaunchDescription( launch_description_source=launch.LaunchDescriptionSource( launch_description=launch_ros. get_default_launch_description( rclpy_context=self._rclpy_context, ))) ]
def run_rviz(_): rviz_node = Node( package='rviz2', node_executable='rviz2', on_exit=launch.actions.Shutdown() ) rviz = launch.LaunchDescription([ rviz_node ]) desc_source = launch.LaunchDescriptionSource(rviz) return launch.actions.IncludeLaunchDescription( launch_description_source=desc_source )
def run(self): """ Launch the processes under test and run the tests. :return: A tuple of two unittest.Results - one for tests that ran while processes were active, and another set for tests that ran after processes were shutdown """ test_ld, test_context = _normalize_ld(self._gen_launch_description_fn)( lambda: self._processes_launched.set()) # Data to squirrel away for post-shutdown tests self.proc_info = ActiveProcInfoHandler() self.proc_output = ActiveIoHandler() self.test_context = test_context parsed_launch_arguments = parse_launch_arguments( self._launch_file_arguments) self.test_args = {} for k, v in parsed_launch_arguments: self.test_args[k] = v # Wrap the test_ld in another launch description so we can bind command line arguments to # the test and add our own event handlers for process IO and process exit: launch_description = LaunchDescription([ launch.actions.IncludeLaunchDescription( launch.LaunchDescriptionSource(launch_description=test_ld), launch_arguments=parsed_launch_arguments), RegisterEventHandler( OnProcessExit( on_exit=lambda info, unused: self.proc_info.append(info))), RegisterEventHandler( OnProcessIO( on_stdout=self.proc_output.append, on_stderr=self.proc_output.append, )), ]) self._launch_service.include_launch_description(launch_description) self._test_tr.start() # Run the tests on another thread self._launch_service.run( ) # This will block until the test thread stops it if not self._tests_completed.wait(timeout=0): # LaunchService.run returned before the tests completed. This can be because the user # did ctrl+c, or because all of the launched nodes died before the tests completed print("Processes under test stopped before tests completed") self._print_process_output_summary( ) # <-- Helpful to debug why processes died early # We treat this as a test failure and return some test results indicating such return FailResult(), FailResult() # Now, run the post-shutdown tests inactive_suite = PostShutdownTestLoader( injected_attributes={ "proc_info": self.proc_info, "proc_output": self.proc_output._io_handler, "test_args": self.test_args, }, injected_args=dict( self.test_context, # Add a few more things to the args dictionary: **{ "proc_info": self.proc_info, "proc_output": self.proc_output._io_handler, "test_args": self.test_args })).loadTestsFromModule(self._test_module) inactive_results = unittest.TextTestRunner( verbosity=2, resultclass=TestResult).run(inactive_suite) return self._results, inactive_results
def run(self): """ Launch the processes under test and run the tests. :return: A tuple of two unittest.Results - one for tests that ran while processes were active, and another set for tests that ran after processes were shutdown """ test_ld, test_context = self._test_run.normalized_test_description( ready_fn=lambda: self._processes_launched.set()) # Data that needs to be bound to the tests: proc_info = ActiveProcInfoHandler() proc_output = ActiveIoHandler() full_context = dict(test_context, **self._test_run.param_args) # TODO pete: this can be simplified as a call to the dict ctor: parsed_launch_arguments = parse_launch_arguments( self._launch_file_arguments) test_args = {} for k, v in parsed_launch_arguments: test_args[k] = v self._test_run.bind( self._test_run.pre_shutdown_tests, injected_attributes={ 'proc_info': proc_info, 'proc_output': proc_output, 'test_args': test_args, }, injected_args=dict( full_context, # Add a few more things to the args dictionary: **{ 'proc_info': proc_info, 'proc_output': proc_output, 'test_args': test_args })) self._test_run.bind( self._test_run.post_shutdown_tests, injected_attributes={ 'proc_info': proc_info._proc_info_handler, 'proc_output': proc_output._io_handler, 'test_args': test_args, }, injected_args=dict( full_context, # Add a few more things to the args dictionary: **{ 'proc_info': proc_info._proc_info_handler, 'proc_output': proc_output._io_handler, 'test_args': test_args })) # Wrap the test_ld in another launch description so we can bind command line arguments to # the test and add our own event handlers for process IO and process exit: launch_description = LaunchDescription([ launch.actions.IncludeLaunchDescription( launch.LaunchDescriptionSource(launch_description=test_ld), launch_arguments=parsed_launch_arguments), RegisterEventHandler( OnProcessExit( on_exit=lambda info, unused: proc_info.append(info))), RegisterEventHandler( OnProcessIO( on_stdout=proc_output.append, on_stderr=proc_output.append, )), ]) self._launch_service.include_launch_description(launch_description) self._test_tr.start() # Run the tests on another thread self._launch_service.run( ) # This will block until the test thread stops it if not self._tests_completed.wait(timeout=0): # LaunchService.run returned before the tests completed. This can be because the user # did ctrl+c, or because all of the launched nodes died before the tests completed print('Processes under test stopped before tests completed') # Give some extra help debugging why processes died early self._print_process_output_summary(proc_info, proc_output) # We treat this as a test failure and return some test results indicating such raise _LaunchDiedException() inactive_results = unittest.TextTestRunner( verbosity=2, resultclass=TestResult).run(self._test_run.post_shutdown_tests) self._results.append(inactive_results) return self._results
def run(self): """ Launch the nodes under test and run the tests. :return: A tuple of two unittest.Results - one for tests that ran while nodes were active, and another set for tests that ran after nodes were shutdown """ test_ld = self._gen_launch_description_fn( lambda: self._nodes_launched.set()) # Data to squirrel away for post-shutdown tests self.proc_info = ActiveProcInfoHandler() self.proc_output = ActiveIoHandler() parsed_launch_arguments = parse_launch_arguments( self._launch_file_arguments) self.test_args = {} for k, v in parsed_launch_arguments: self.test_args[k] = v # Wrap the test_ld in another launch description so we can bind command line arguments to # the test and add our own event handlers for process IO and process exit: launch_description = LaunchDescription([ launch.actions.IncludeLaunchDescription( launch.LaunchDescriptionSource(launch_description=test_ld), launch_arguments=parsed_launch_arguments), RegisterEventHandler( OnProcessExit( on_exit=lambda info, unused: self.proc_info.append(info))), RegisterEventHandler( OnProcessIO( on_stdout=self.proc_output.append, on_stderr=self.proc_output.append, )), ]) self._launch_service.include_launch_description(launch_description) self._test_tr.start() # Run the tests on another thread self._launch_service.run( ) # This will block until the test thread stops it if not self._tests_completed.wait(timeout=0): # LaunchService.run returned before the tests completed. This can be because the user # did ctrl+c, or because all of the launched nodes died before the tests completed # We should treat this as a test failure and return some test results indicating such print("Nodes under test stopped before tests completed") # TODO: This will make the program exit with an exit code, but it's not apparent # why. Consider having apex_rostest_main print some summary return _fail_result(), _fail_result() # Now, run the post-shutdown tests inactive_suite = PostShutdownTestLoader().loadTestsFromModule( self._test_module) self._give_attribute_to_tests(self.proc_info, "proc_info", inactive_suite) self._give_attribute_to_tests(self.proc_output._io_handler, "proc_output", inactive_suite) self._give_attribute_to_tests(self.test_args, "test_args", inactive_suite) inactive_results = unittest.TextTestRunner( verbosity=2, resultclass=TestResult).run(inactive_suite) return self._results, inactive_results