def generate_launch_description(): return LaunchDescription([ Trace( session_name='profile', events_ust=[ 'lttng_ust_cyg_profile_fast:func_entry', 'lttng_ust_cyg_profile_fast:func_exit', 'lttng_ust_statedump:start', 'lttng_ust_statedump:end', 'lttng_ust_statedump:bin_info', 'lttng_ust_statedump:build_id', ] + DEFAULT_EVENTS_ROS, events_kernel=[ 'sched_switch', ], context_fields={ 'kernel': DEFAULT_CONTEXT, 'userspace': DEFAULT_CONTEXT + ['ip'], }, ), Node( package='test_tracetools', executable='test_ping', arguments=['do_more'], output='screen', ), Node( package='test_tracetools', executable='test_pong', arguments=['do_more'], output='screen', ), ])
def test_action_context_per_domain(self) -> None: self.assertIsNone(os.environ.get('LD_PRELOAD')) tmpdir = tempfile.mkdtemp( prefix='TestTraceAction__test_action_context_per_domain') action = Trace( session_name='my-session-name', base_path=tmpdir, events_kernel=[], events_ust=[ 'ros2:*', '*', ], context_fields={ 'kernel': [], 'userspace': ['vpid', 'vtid'], }, ) self._assert_launch_no_errors([action]) self._check_trace_action(action, tmpdir) self.assertDictEqual( action.context_fields, { 'kernel': [], 'userspace': ['vpid', 'vtid'], }, ) shutil.rmtree(tmpdir) del os.environ['LD_PRELOAD']
def generate_launch_description(): return LaunchDescription([ Trace( session_name='memory-usage', events_ust=[ 'lttng_ust_libc:malloc', 'lttng_ust_libc:calloc', 'lttng_ust_libc:realloc', 'lttng_ust_libc:free', 'lttng_ust_libc:memalign', 'lttng_ust_libc:posix_memalign', ] + DEFAULT_EVENTS_ROS, events_kernel=[ 'kmem_mm_page_alloc', 'kmem_mm_page_free', ], ), Node( package='test_tracetools', executable='test_ping', arguments=['do_more'], output='screen', ), Node( package='test_tracetools', executable='test_pong', arguments=['do_more'], output='screen', ), ])
def test_action_ld_preload(self) -> None: self.assertIsNone(os.environ.get('LD_PRELOAD')) tmpdir = tempfile.mkdtemp( prefix='TestTraceAction__test_action_ld_preload') action = Trace( session_name='my-session-name', base_path=tmpdir, events_kernel=[], events_ust=[ 'lttng_ust_cyg_profile_fast:*', 'lttng_ust_libc:*', 'ros2:*', 'lttng_ust_pthread:*', 'lttng_ust_dl:*', ], ) node_ping_action = Node( package='test_tracetools', executable='test_ping', output='screen', ) node_pong_action = Node( package='test_tracetools', executable='test_pong', output='screen', ) self._assert_launch_no_errors( [action, node_ping_action, node_pong_action]) self._check_trace_action( action, tmpdir, events_ust=[ 'lttng_ust_cyg_profile_fast:*', 'lttng_ust_libc:*', 'ros2:*', 'lttng_ust_pthread:*', 'lttng_ust_dl:*', ], ) # Check that LD_PRELOAD was set accordingly ld_preload = os.environ.get('LD_PRELOAD') assert ld_preload is not None paths = ld_preload.split(':') self.assertEqual(4, len(paths)) self.assertTrue( any(p.endswith('liblttng-ust-cyg-profile-fast.so') for p in paths)) self.assertTrue( any(p.endswith('liblttng-ust-libc-wrapper.so') for p in paths)) self.assertTrue( any(p.endswith('liblttng-ust-pthread-wrapper.so') for p in paths)) self.assertTrue(any(p.endswith('liblttng-ust-dl.so') for p in paths)) shutil.rmtree(tmpdir) del os.environ['LD_PRELOAD']
def generate_launch_description(): return LaunchDescription([ Trace( session_name='clock_recorder', events_kernel=[], events_ust=['rostime:ros_time'] ), Node( package='clock_recorder', executable='recorder' ) ])
def run_and_trace( base_path: str, session_name_prefix: str, ros_events: List[str], kernel_events: List[str], package_name: str, node_names: List[str], additional_actions: Union[List[Action], Action] = [], ) -> Tuple[int, str]: """ Run a node while tracing. :param base_path: the base path where to put the trace directory :param session_name_prefix: the session name prefix for the trace directory :param ros_events: the list of ROS UST events to enable :param kernel_events: the list of kernel events to enable :param package_name: the name of the package to use :param node_names: the names of the nodes to execute :param additional_actions: the list of additional actions to prepend :return: exit code, full generated path """ session_name = append_timestamp(session_name_prefix) full_path = os.path.join(base_path, session_name) if not isinstance(additional_actions, list): additional_actions = [additional_actions] launch_actions = additional_actions # Add trace action launch_actions.append( Trace( session_name=session_name, append_timestamp=False, base_path=base_path, events_ust=ros_events, events_kernel=kernel_events, )) # Add nodes for node_name in node_names: n = Node( package=package_name, executable=node_name, output='screen', ) launch_actions.append(n) ld = LaunchDescription(launch_actions) ls = LaunchService() ls.include_launch_description(ld) exit_code = ls.run() return exit_code, full_path
def generate_launch_description(): return LaunchDescription([ Trace(session_name='my-tracing-session', ), Node( package='test_tracetools', executable='test_ping', output='screen', ), Node( package='test_tracetools', executable='test_pong', output='screen', ), ])
def test_action_substitutions(self) -> None: self.assertIsNone(os.environ.get('LD_PRELOAD')) tmpdir = tempfile.mkdtemp( prefix='TestTraceAction__test_action_substitutions') self.assertIsNone(os.environ.get('TestTraceAction__event_ust', None)) os.environ['TestTraceAction__event_ust'] = 'ros2:*' self.assertIsNone( os.environ.get('TestTraceAction__context_field', None)) os.environ['TestTraceAction__context_field'] = 'vpid' session_name_arg = DeclareLaunchArgument( 'session-name', default_value='my-session-name', description='the session name', ) action = Trace( session_name=LaunchConfiguration(session_name_arg.name), base_path=TextSubstitution(text=tmpdir), events_kernel=[], events_ust=[ EnvironmentVariable(name='TestTraceAction__event_ust'), TextSubstitution(text='*'), ], context_fields={ 'kernel': [], 'userspace': [ EnvironmentVariable(name='TestTraceAction__context_field'), TextSubstitution(text='vtid'), ], }, ) self._assert_launch_no_errors([session_name_arg, action]) self._check_trace_action(action, tmpdir) self.assertDictEqual( action.context_fields, { 'kernel': [], 'userspace': ['vpid', 'vtid'], }, ) shutil.rmtree(tmpdir) del os.environ['TestTraceAction__event_ust'] del os.environ['TestTraceAction__context_field'] del os.environ['LD_PRELOAD']
def generate_launch_description(): return LaunchDescription([ Trace( session_name='lifecycle-node-state', events_kernel=[], ), Node( package='test_tracetools', executable='test_lifecycle_node', output='screen', ), Node( package='test_tracetools', executable='test_lifecycle_client', output='screen', ), ])
def test_action(self) -> None: self.assertIsNone(os.environ.get('LD_PRELOAD')) tmpdir = tempfile.mkdtemp(prefix='TestTraceAction__test_action') # Disable kernel events just to not require kernel tracing for the test action = Trace( session_name='my-session-name', base_path=tmpdir, events_kernel=[], events_ust=[ 'ros2:*', '*', ], ) self._assert_launch_no_errors([action]) self._check_trace_action(action, tmpdir) shutil.rmtree(tmpdir) del os.environ['LD_PRELOAD']
def generate_launch_description(): return LaunchDescription([ Trace( session_name='pingpong', events_kernel=[], ), Node( package='test_tracetools', executable='test_ping', arguments=['do_more'], output='screen', ), Node( package='test_tracetools', executable='test_pong', arguments=['do_more'], output='screen', ), ])
def generate_launch_description(): # Get the bringup directory bringup_dir = FindPackageShare('pendulum_bringup').find('pendulum_bringup') # Set robot description parameters urdf_file = os.path.join(bringup_dir, 'urdf', 'pendulum.urdf') with open(urdf_file, 'r') as infp: robot_desc = infp.read() rsp_params = {'robot_description': robot_desc} # Set parameter file path param_file_path = os.path.join(bringup_dir, 'params', 'pendulum.param.yaml') param_file = launch.substitutions.LaunchConfiguration( 'params', default=[param_file_path]) # Set rviz config path rviz_cfg_path = os.path.join(bringup_dir, 'rviz/pendulum.rviz') # Create the launch configuration variables autostart_param = DeclareLaunchArgument( name='autostart', default_value='True', description='Automatically start lifecycle nodes') priority_param = DeclareLaunchArgument(name='priority', default_value='0', description='Set process priority') cpu_affinity_param = DeclareLaunchArgument( name='cpu-affinity', default_value='0', description='Set process CPU affinity') with_lock_memory_param = DeclareLaunchArgument( name='lock-memory', default_value='False', description='Lock the process memory') lock_memory_size_param = DeclareLaunchArgument( name='lock-memory-size', default_value='0', description='Set lock memory size in MB') config_child_threads_param = DeclareLaunchArgument( name='config-child-threads', default_value='False', description='Configure process child threads (typically DDS threads)') driver_enable_param = DeclareLaunchArgument( name='driver-enable', default_value='True', description='Enable/disable pendulum driver nodes') controller_enable_param = DeclareLaunchArgument( name='controller-enable', default_value='True', description='Enable/disable controller driver nodes') with_rviz_param = DeclareLaunchArgument( 'rviz', default_value='False', description='Launch RVIZ2 in addition to other nodes') trace_param = DeclareLaunchArgument( 'trace', default_value='False', description='Launch ROS tracing action') trace_memory_param = DeclareLaunchArgument( 'trace-memory', default_value='False', description= 'Launch ROS tracing action with memory functions tracing enabled') # Node definitions pendulum_demo_runner = Node( package='pendulum_demo', executable='pendulum_demo', output='screen', parameters=[param_file], arguments=[ '--autostart', LaunchConfiguration('autostart'), '--priority', LaunchConfiguration('priority'), '--cpu-affinity', LaunchConfiguration('cpu-affinity'), '--lock-memory', LaunchConfiguration('lock-memory'), '--lock-memory-size', LaunchConfiguration('lock-memory-size'), '--config-child-threads', LaunchConfiguration('config-child-threads'), '--driver-enable', LaunchConfiguration('driver-enable'), '--controller-enable', LaunchConfiguration('controller-enable'), ]) robot_state_publisher_runner = Node(package='robot_state_publisher', executable='robot_state_publisher', output='screen', parameters=[rsp_params], condition=IfCondition( LaunchConfiguration('rviz'))) rviz_runner = Node(package='rviz2', executable='rviz2', name='rviz2', arguments=['-d', str(rviz_cfg_path)], condition=IfCondition(LaunchConfiguration('rviz'))) # Create tracing runners ros_tracing = Trace(session_name='pendulum', events_kernel=[], condition=IfCondition(LaunchConfiguration('trace'))) ros_tracing_memory_usage = Trace(session_name='pendulum-memory-usage', events_ust=[ 'lttng_ust_libc:malloc', 'lttng_ust_libc:calloc', 'lttng_ust_libc:realloc', 'lttng_ust_libc:free', 'lttng_ust_libc:memalign', 'lttng_ust_libc:posix_memalign', ] + DEFAULT_EVENTS_ROS, events_kernel=[ 'kmem_mm_page_alloc', 'kmem_mm_page_free', ], condition=IfCondition( LaunchConfiguration('trace-memory'))) return LaunchDescription([ trace_param, trace_memory_param, ros_tracing, ros_tracing_memory_usage, autostart_param, priority_param, cpu_affinity_param, with_lock_memory_param, lock_memory_size_param, config_child_threads_param, driver_enable_param, controller_enable_param, with_rviz_param, robot_state_publisher_runner, pendulum_demo_runner, rviz_runner ])