diff --git a/ros2caret/verb/caret_record_init.py b/ros2caret/verb/caret_record_init.py index 3ee2e3d6..48ee1839 100644 --- a/ros2caret/verb/caret_record_init.py +++ b/ros2caret/verb/caret_record_init.py @@ -53,6 +53,7 @@ def init( subbuffer_size_kernel: int, display_list: bool = False, append_trace: bool = True, + immediate: bool = False, ) -> bool: """ Init and start tracing. @@ -101,7 +102,8 @@ def init( print(f'writing tracing session to: {full_session_path}') - input('press enter to start...') + if not immediate: + input('press enter to start...') # for iron, rolling if os.environ['ROS_DISTRO'] in ['iron', 'rolling']: trace_directory = lttng.lttng_init( diff --git a/ros2caret/verb/record.py b/ros2caret/verb/record.py index 7c0a5d99..b70efedf 100644 --- a/ros2caret/verb/record.py +++ b/ros2caret/verb/record.py @@ -146,6 +146,9 @@ def add_arguments(self, parser, cli_name): 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. ') + parser.add_argument( + '--immediate', dest='immediate', action='store_true', + help='record immediately. ') def main(self, *, args): if args.light_mode: @@ -202,6 +205,7 @@ def main(self, *, args): 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_args['immediate'] = args.immediate init(**init_args) def _run():