Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat: support subbuffer size option #85

Merged
merged 15 commits into from
Oct 5, 2023
6 changes: 6 additions & 0 deletions ros2caret/verb/caret_record_init.py
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,8 @@ def init(
ros_events: List[str],
kernel_events: List[str],
context_fields: List[str],
subbuffer_size_ust: int,
subbuffer_size_kernel: int,
display_list: bool = False,
append_trace: bool = True,
) -> bool:
Expand All @@ -66,6 +68,8 @@ def init(
:param kernel_events: list of kernel events to enable
:param context_fields: list of context fields to enable
:param display_list: whether to display list(s) of enabled events and context names
:param subbuffer_size_ust: the size of the subbuffers for userspace events
:param subbuffer_size_kernel: the size of the subbuffers for kernel events
:return: True if successful, False otherwise
"""
# Check if LTTng is installed right away before printing anything
Expand Down Expand Up @@ -107,6 +111,8 @@ def init(
ros_events=ros_events,
kernel_events=kernel_events,
context_fields=context_fields,
subbuffer_size_ust=subbuffer_size_ust,
subbuffer_size_kernel=subbuffer_size_kernel,
)
# for humble
else:
Expand Down
29 changes: 29 additions & 0 deletions ros2caret/verb/record.py
Original file line number Diff line number Diff line change
Expand Up @@ -134,6 +134,18 @@ def add_arguments(self, parser, cli_name):
parser.add_argument(
'--light', dest='light_mode', action='store_true',
help='light mode (record high level events only)')
parser.add_argument(
'--subbuffer-size-ust', dest='subbuffer_size_ust', type=int,
default=8*4096,
help='the size of the subbuffers for userspace events(default: 8*4096). '
'buffer size must be power of two. '
'available in iron or rolling only. ')
parser.add_argument(
'--subbuffer-size-kernel', dest='subbuffer_size_kernel', type=int,
default=32*4096,
help='the size of the subbuffers for kernel events(default: 32*4096). '
'buffer size must be power of two. '
'available in iron or rolling only. ')

def main(self, *, args):
if args.light_mode:
Expand Down Expand Up @@ -171,6 +183,23 @@ def main(self, *, args):
else:
init_args['context_fields'] = context_names
init_args['display_list'] = args.list
# Note: keyword argument --subbuffer_size_ust/kernel are available in iron or rolling.

if os.environ['ROS_DISTRO'] not in ['iron', 'rolling'] \
and args.subbuffer_size_ust != 8*4096:
raise ValueError('the --subbuffer-size-ust option is '
'available in iron or rolling')
if args.subbuffer_size_ust & (args.subbuffer_size_ust-1):
raise ValueError('--subbuffer-size-ust value must be power of two.')
init_args['subbuffer_size_ust'] = args.subbuffer_size_ust

if os.environ['ROS_DISTRO'] not in ['iron', 'rolling'] \
and args.subbuffer_size_kernel != 32*4096:
raise ValueError('the --subbuffer-size-kernel option is '
'available in iron or rolling')
if args.subbuffer_size_kernel & (args.subbuffer_size_kernel-1):
raise ValueError('--subbuffer-size-kernel value must be power of two.')
init_args['subbuffer_size_kernel'] = args.subbuffer_size_kernel
init(**init_args)

def _run():
Expand Down