Fix non-copyright linting errors in tracetools_trace

This commit is contained in:
Christophe Bedard 2019-06-06 09:39:02 +02:00
parent 04efe73f70
commit 58a58de3d4
3 changed files with 135 additions and 67 deletions

View file

@ -1,15 +1,26 @@
# LTTng tracing interface # LTTng tracing interface
# Temporary workaround
import sys import sys
import lttng
from .names import (
DEFAULT_CONTEXT,
DEFAULT_EVENTS_KERNEL,
DEFAULT_EVENTS_ROS,
)
# Temporary workaround
sys.path = ['/usr/local/lib/python3.6/site-packages'] + sys.path sys.path = ['/usr/local/lib/python3.6/site-packages'] + sys.path
from lttng import *
from .names import DEFAULT_EVENTS_ROS, DEFAULT_EVENTS_KERNEL, DEFAULT_CONTEXT
def lttng_setup(session_name, full_path, ros_events=DEFAULT_EVENTS_ROS, kernel_events=DEFAULT_EVENTS_KERNEL, context_names=DEFAULT_CONTEXT): def lttng_setup(session_name, full_path,
ros_events=DEFAULT_EVENTS_ROS,
kernel_events=DEFAULT_EVENTS_KERNEL,
context_names=DEFAULT_CONTEXT):
""" """
Setup LTTng session, with events and context Set up LTTng session, with events and context.
:param session_name (str): the name of the session :param session_name (str): the name of the session
:param full_path (str): the full path to the main directory to write trace data to :param full_path (str): the full path to the main directory to write trace data to
:param ros_events (list(str)): list of ROS events to enable :param ros_events (list(str)): list of ROS events to enable
@ -21,30 +32,30 @@ def lttng_setup(session_name, full_path, ros_events=DEFAULT_EVENTS_ROS, kernel_e
# Domains # Domains
if ust_enabled: if ust_enabled:
domain_ust = Domain() domain_ust = lttng.Domain()
domain_ust.type = DOMAIN_UST domain_ust.type = lttng.DOMAIN_UST
domain_ust.buf_type = BUFFER_PER_UID domain_ust.buf_type = lttng.BUFFER_PER_UID
channel_ust = Channel() channel_ust = lttng.Channel()
channel_ust.name = 'ros2' channel_ust.name = 'ros2'
channel_ust.attr.overwrite = 0 channel_ust.attr.overwrite = 0
channel_ust.attr.subbuf_size = 2*4096 channel_ust.attr.subbuf_size = 2*4096
channel_ust.attr.num_subbuf = 8 channel_ust.attr.num_subbuf = 8
channel_ust.attr.switch_timer_interval = 0 channel_ust.attr.switch_timer_interval = 0
channel_ust.attr.read_timer_interval = 200 channel_ust.attr.read_timer_interval = 200
channel_ust.attr.output = EVENT_MMAP channel_ust.attr.output = lttng.EVENT_MMAP
events_list_ust = _create_events(ros_events) events_list_ust = _create_events(ros_events)
if kernel_enabled: if kernel_enabled:
domain_kernel = Domain() domain_kernel = lttng.Domain()
domain_kernel.type = DOMAIN_KERNEL domain_kernel.type = lttng.DOMAIN_KERNEL
domain_kernel.buf_type = BUFFER_GLOBAL domain_kernel.buf_type = lttng.BUFFER_GLOBAL
channel_kernel = Channel() channel_kernel = lttng.Channel()
channel_kernel.name = 'kchan' channel_kernel.name = 'kchan'
channel_kernel.attr.overwrite = 0 channel_kernel.attr.overwrite = 0
channel_kernel.attr.subbuf_size = 8*4096 channel_kernel.attr.subbuf_size = 8*4096
channel_kernel.attr.num_subbuf = 8 channel_kernel.attr.num_subbuf = 8
channel_kernel.attr.switch_timer_interval = 0 channel_kernel.attr.switch_timer_interval = 0
channel_kernel.attr.read_timer_interval = 200 channel_kernel.attr.read_timer_interval = 200
channel_kernel.attr.output = EVENT_MMAP channel_kernel.attr.output = lttng.EVENT_MMAP
events_list_kernel = _create_events(kernel_events) events_list_kernel = _create_events(kernel_events)
# Session # Session
@ -61,121 +72,166 @@ def lttng_setup(session_name, full_path, ros_events=DEFAULT_EVENTS_ROS, kernel_e
handle_kernel = _create_handle(session_name, domain_kernel) handle_kernel = _create_handle(session_name, domain_kernel)
_enable_channel(handle_kernel, channel_kernel) _enable_channel(handle_kernel, channel_kernel)
_enable_events(handle_kernel, events_list_kernel, channel_kernel.name) _enable_events(handle_kernel, events_list_kernel, channel_kernel.name)
# Context # Context
context_list = _create_context_list(context_names) context_list = _create_context_list(context_names)
enabled_handles = [h for h in [handle_ust, handle_kernel] if h is not None] enabled_handles = [h for h in [handle_ust, handle_kernel] if h is not None]
_add_context(enabled_handles, context_list) _add_context(enabled_handles, context_list)
def lttng_start(session_name): def lttng_start(session_name):
""" """
Start LTTng session, and check for errors Start LTTng session, and check for errors.
:param session_name (str): the name of the session
""" """
result = start(session_name) result = lttng.start(session_name)
if result < 0: if result < 0:
raise RuntimeError(f'failed to start tracing: {strerror(result)}') raise RuntimeError(f'failed to start tracing: {lttng.strerror(result)}')
def lttng_stop(session_name): def lttng_stop(session_name):
""" """
Stop LTTng session, and check for errors Stop LTTng session, and check for errors.
:param session_name (str): the name of the session
""" """
result = stop(session_name) result = lttng.stop(session_name)
if result < 0: if result < 0:
raise RuntimeError(f'failed to stop tracing: {strerror(result)}') raise RuntimeError(f'failed to stop tracing: {lttng.strerror(result)}')
def lttng_destroy(session_name): def lttng_destroy(session_name):
""" """
Destroy LTTng session, and check for errors Destroy LTTng session, and check for errors.
:param session_name (str): the name of the session
""" """
result = destroy(session_name) result = lttng.destroy(session_name)
if result < 0: if result < 0:
raise RuntimeError(f'failed to destroy tracing session: {strerror(result)}') raise RuntimeError(f'failed to destroy tracing session: {lttng.strerror(result)}')
def _create_events(event_names_list): def _create_events(event_names_list):
""" """
Create events list from names Create events list from names.
:param event_names_list (list(str)): a list of names to create events for
:return (list(Event)): the list of events
""" """
events_list = [] events_list = []
for event_name in event_names_list: for event_name in event_names_list:
e = Event() e = lttng.Event()
e.name = event_name e.name = event_name
e.type = EVENT_TRACEPOINT e.type = lttng.EVENT_TRACEPOINT
e.loglevel_type = EVENT_LOGLEVEL_ALL e.loglevel_type = lttng.EVENT_LOGLEVEL_ALL
events_list.append(e) events_list.append(e)
return events_list return events_list
def _create_session(session_name, full_path): def _create_session(session_name, full_path):
""" """
Create session from name and full directory path, and check for errors Create session from name and full directory path, and check for errors.
:param session_name (str): the name of the session
:param full_path (str): the full path to the main directory to write trace data to
""" """
result = create(session_name, full_path) result = lttng.create(session_name, full_path)
LTTNG_ERR_EXIST_SESS = 28 LTTNG_ERR_EXIST_SESS = 28
if result == -LTTNG_ERR_EXIST_SESS: if result == -LTTNG_ERR_EXIST_SESS:
# Sessions seem to persist, so if it already exists, # Sessions seem to persist, so if it already exists,
# just destroy it and try again # just destroy it and try again
lttng_destroy(session_name) lttng_destroy(session_name)
result = create(session_name, full_path) result = lttng.create(session_name, full_path)
if result < 0: if result < 0:
raise RuntimeError(f'session creation failed: {strerror(result)}') raise RuntimeError(f'session creation failed: {lttng.strerror(result)}')
def _create_handle(session_name, domain): def _create_handle(session_name, domain):
""" """
Create a handle for a given session name and a domain, and check for errors Create a handle for a given session name and a domain, and check for errors.
:param session_name (str): the name of the session
:param domain (Domain): the domain to be used
:return (Handle): the handle
""" """
handle = None handle = None
handle = Handle(session_name, domain) handle = lttng.Handle(session_name, domain)
if handle is None: if handle is None:
raise RuntimeError('handle creation failed') raise RuntimeError('handle creation failed')
return handle return handle
def _enable_channel(handle, channel): def _enable_channel(handle, channel):
""" """
Enable channel for a handle, and check for errors Enable channel for a handle, and check for errors.
:param handle (Handle): the handle to be used
:param channel (Channel): the channel to enable
""" """
result = enable_channel(handle, channel) result = lttng.enable_channel(handle, channel)
if result < 0: if result < 0:
raise RuntimeError(f'channel enabling failed: {strerror(result)}') raise RuntimeError(f'channel enabling failed: {lttng.strerror(result)}')
def _enable_events(handle, events_list, channel_name): def _enable_events(handle, events_list, channel_name):
""" """
Enable events list for a given handle and channel name, and check for errors Enable events list for a given handle and channel name, and check for errors.
:param handle (Handle): the handle to be used
:param events_list (list(Event)): the list of events to enable
:param channel_name (str): the name of the channel to associate
""" """
for event in events_list: for event in events_list:
result = enable_event(handle, event, channel_name) result = lttng.enable_event(handle, event, channel_name)
if result < 0: if result < 0:
raise RuntimeError(f'event enabling failed: {strerror(result)}') raise RuntimeError(f'event enabling failed: {lttng.strerror(result)}')
context_map = { context_map = {
'procname': EVENT_CONTEXT_PROCNAME, 'procname': lttng.EVENT_CONTEXT_PROCNAME,
'pid': EVENT_CONTEXT_PID, 'pid': lttng.EVENT_CONTEXT_PID,
'vpid': EVENT_CONTEXT_VPID, 'vpid': lttng.EVENT_CONTEXT_VPID,
'vtid': EVENT_CONTEXT_VTID, 'vtid': lttng.EVENT_CONTEXT_VTID,
} }
def _context_name_to_type(context_name): def _context_name_to_type(context_name):
""" """
Convert from context name to LTTng enum/constant type Convert from context name to LTTng enum/constant type.
:param context_name (str): the generic name for the context
:return (int): the associated type
""" """
return context_map.get(context_name) return context_map.get(context_name)
def _create_context_list(context_names_list): def _create_context_list(context_names_list):
""" """
Create context list from names, and check for errors Create context list from names, and check for errors.
:param context_names_list (list(str)): the list of context names
:return (list(EventContext)): the event context list
""" """
context_list = [] context_list = []
for c in context_names_list: for c in context_names_list:
ec = EventContext() ec = lttng.EventContext()
context_type = _context_name_to_type(c) context_type = _context_name_to_type(c)
if context_type is not None: if context_type is not None:
ec.ctx = context_type ec.ctx = context_type
context_list.append(ec) context_list.append(ec)
return context_list return context_list
def _add_context(handles, context_list): def _add_context(handles, context_list):
""" """
Add context list to given handles, and check for errors Add context list to given handles, and check for errors.
:param handles (list(Handle)): the list of handles for which to add context
:param context_list (list(EventContext)): the list of event contexts to add to the handles
""" """
for handle in handles: for handle in handles:
for contex in context_list: for contex in context_list:
result = add_context(handle, contex, None, None) result = lttng.add_context(handle, contex, None, None)
if result < 0: if result < 0:
raise RuntimeError(f'failed to add context: {strerror(result)}') raise RuntimeError(f'failed to add context: {lttng.strerror(result)}')

View file

@ -1,6 +1,6 @@
# Lists of names (events, context) # Lists of names (events, context)
DEFAULT_EVENTS_KERNEL=[ DEFAULT_EVENTS_KERNEL = [
'block_rq_complete', 'block_rq_complete',
'block_rq_insert', 'block_rq_insert',
'block_rq_issue', 'block_rq_issue',
@ -34,7 +34,7 @@ DEFAULT_EVENTS_KERNEL=[
'timer_hrtimer_expire_exit', 'timer_hrtimer_expire_exit',
] ]
DEFAULT_EVENTS_ROS=[ DEFAULT_EVENTS_ROS = [
'ros2:rcl_init', 'ros2:rcl_init',
'ros2:rcl_node_init', 'ros2:rcl_node_init',
'ros2:rcl_publisher_init', 'ros2:rcl_publisher_init',
@ -54,7 +54,7 @@ DEFAULT_EVENTS_ROS=[
'ros2:rclcpp_callback_register', 'ros2:rclcpp_callback_register',
] ]
DEFAULT_CONTEXT=[ DEFAULT_CONTEXT = [
'procname', 'procname',
'perf:thread:instructions', 'perf:thread:instructions',
'perf:thread:cycles', 'perf:thread:cycles',

View file

@ -1,20 +1,21 @@
#!/usr/bin/env python3 #!/usr/bin/env python3
# Entrypoint/script to setup and start an LTTng tracing session # Entrypoint/script to setup and start an LTTng tracing session
import sys
import time
import argparse import argparse
import time
from tracetools_trace.tools.lttng import ( from tracetools_trace.tools.lttng import (
lttng_destroy,
lttng_setup, lttng_setup,
lttng_start, lttng_start,
lttng_stop, lttng_stop,
lttng_destroy,
) )
from tracetools_trace.tools.names import ( from tracetools_trace.tools.names import (
DEFAULT_EVENTS_ROS,
DEFAULT_EVENTS_KERNEL, DEFAULT_EVENTS_KERNEL,
DEFAULT_EVENTS_ROS,
) )
def main(): def main():
parser = argparse.ArgumentParser(description='Setup and launch an LTTng tracing session.') parser = argparse.ArgumentParser(description='Setup and launch an LTTng tracing session.')
parser.add_argument('--session-name', '-s', dest='session_name', parser.add_argument('--session-name', '-s', dest='session_name',
@ -24,9 +25,14 @@ def main():
default='/tmp', default='/tmp',
help='path of the base directory for trace data (default: %(default)s)') help='path of the base directory for trace data (default: %(default)s)')
parser.add_argument('--ust', '-u', nargs='*', dest='events_ust', default=DEFAULT_EVENTS_ROS, parser.add_argument('--ust', '-u', nargs='*', dest='events_ust', default=DEFAULT_EVENTS_ROS,
help='the ROS UST events to enable (default: all events) [to disable all UST events, provide this flag without any event name]') help='the ROS UST events to enable (default: all events) '
parser.add_argument('--kernel', '-k', nargs='*', dest='events_kernel', default=DEFAULT_EVENTS_KERNEL, '[to disable all UST events, '
help='the kernel events to enable (default: all events) [to disable all UST events, provide this flag without any event name]') 'provide this flag without any event name]')
parser.add_argument('--kernel', '-k', nargs='*', dest='events_kernel',
default=DEFAULT_EVENTS_KERNEL,
help='the kernel events to enable (default: all events) '
'[to disable all UST events, '
'provide this flag without any event name]')
parser.add_argument('--list', '-l', dest='list', action='store_true', parser.add_argument('--list', '-l', dest='list', action='store_true',
help='display lists of enabled events (default: %(default)s)') help='display lists of enabled events (default: %(default)s)')
args = parser.parse_args() args = parser.parse_args()
@ -39,12 +45,18 @@ def main():
ust_enabled = len(ros_events) > 0 ust_enabled = len(ros_events) > 0
kernel_enabled = len(kernel_events) > 0 kernel_enabled = len(kernel_events) > 0
print(f'UST tracing {f"enabled ({len(ros_events)} events)" if ust_enabled else "disabled"}') if ust_enabled:
if args.list and ust_enabled: print(f'UST tracing enabled ({len(ros_events)} events)')
print(f'\tevents: {ros_events}') if args.list:
print(f'kernel tracing {f"enabled ({len(kernel_events)} events)" if kernel_enabled else "disabled"}') print(f'\tevents: {ros_events}')
if args.list and kernel_enabled: else:
print(f'\tevents: {kernel_events}') print('UST tracing disabled')
if kernel_enabled:
print(f'kernel tracing enabled ({len(kernel_events)} events)')
if args.list:
print(f'\tevents: {kernel_events}')
else:
print('kernel tracing disabled')
lttng_setup(session_name, full_path, ros_events=ros_events, kernel_events=kernel_events) lttng_setup(session_name, full_path, ros_events=ros_events, kernel_events=kernel_events)
print(f'writting tracing session to: {full_path}') print(f'writting tracing session to: {full_path}')