26 use_sim_time = LaunchConfiguration("use_sim_time")
27 slam_params_file = LaunchConfiguration("slam_params_file")
28
29 declare_use_sim_time_argument = DeclareLaunchArgument(
30 "use_sim_time", default_value="true", description="Use simulation/Gazebo clock"
31 )
32 declare_slam_params_file_cmd = DeclareLaunchArgument(
33 "slam_params_file",
34 default_value=os.path.join(
35 get_package_share_directory("sm_aws_warehouse_navigation"),
36 "params",
37 "mapper_params_online_sync.yaml",
38 ),
39 description="Full path to the ROS2 parameters file to use for the slam_toolbox node",
40 )
41
42 start_sync_slam_toolbox_node = Node(
43 parameters=[slam_params_file, {"use_sim_time": use_sim_time}],
44 package="slam_toolbox",
45 executable="sync_slam_toolbox_node",
46 name="slam_toolbox",
47 output="screen",
48 )
49
50 ld = LaunchDescription()
51
52 ld.add_action(declare_use_sim_time_argument)
53 ld.add_action(declare_slam_params_file_cmd)
54 ld.add_action(start_sync_slam_toolbox_node)
55
56 return ld
def generate_launch_description()