15 from pathlib
import Path
16 from typing
import List
18 from ament_index_python.packages
import get_package_share_directory
20 from launch
import LaunchDescription
21 from launch.actions
import DeclareLaunchArgument
22 from launch.actions
import GroupAction
23 from launch.actions
import ExecuteProcess
24 from launch.actions
import Shutdown
25 from launch.utilities.type_utils
import get_typed_value
27 from launch_ros.actions
import SetParameter
33 example_dir_path = Path(get_package_share_directory(
'beluga_example'))
35 DeclareLaunchArgument(
37 default_value=
'False',
38 description=
'Start the rosbag player in a paused state.',
40 DeclareLaunchArgument(
43 description=
'Rate used to playback the bag.',
45 DeclareLaunchArgument(
47 default_value=str(example_dir_path /
'bags' /
'perfect_odometry'),
48 description=
'Path of the rosbag to playback.',
50 DeclareLaunchArgument(
52 default_value=
'False',
53 description=
'Whether to record a bagfile or not.',
55 DeclareLaunchArgument(
56 name=
'topics_to_record',
57 default_value=
'[/tf, /amcl_pose, /pose, /odometry/ground_truth]',
58 description=
'Topics to record in a new bagfile.',
60 DeclareLaunchArgument(
61 name=
'bagfile_output',
63 description=
'Destination bagfile to create, defaults to timestamped folder',
77 start_paused = get_typed_value(start_paused, bool)
78 record_bag = get_typed_value(record_bag, bool)
79 topics_to_record = get_typed_value(topics_to_record, List[str])
92 bag_play_cmd.append(
'--start-paused')
96 other_args = topics_to_record
97 if bagfile_output !=
'':
98 other_args.extend((
'-o', bagfile_output))
101 cmd=[
'ros2',
'bag',
'record', *other_args],
106 load_nodes = GroupAction(
108 SetParameter(
'use_sim_time',
True),
112 on_exit=[Shutdown()],
118 return LaunchDescription([load_nodes])