2929from launch .substitutions import LaunchConfiguration , PathJoinSubstitution
3030from launch_ros .actions import PushRosNamespace , SetRemap
3131
32+ from nav2_common .launch import RewrittenYaml
33+
3234pkg_turtlebot4_navigation = get_package_share_directory ('turtlebot4_navigation' )
3335pkg_slam_toolbox = get_package_share_directory ('slam_toolbox' )
3436
@@ -71,22 +73,29 @@ def launch_setup(context, *args, **kwargs):
7173 launch_slam_async = PathJoinSubstitution (
7274 [pkg_slam_toolbox , 'launch' , 'online_async_launch.py' ])
7375
76+ rewritten_slam_params = RewrittenYaml (
77+ source_file = slam_params ,
78+ root_key = namespace_str ,
79+ param_rewrites = {
80+ 'map_name' : namespace_str + '/map' ,
81+ 'scan_topic' : namespace_str + '/scan' ,
82+ },
83+ convert_types = True ,
84+ )
85+
7486 slam = GroupAction ([
7587 PushRosNamespace (namespace ),
7688
7789 SetRemap ('/tf' , namespace_str + '/tf' ),
7890 SetRemap ('/tf_static' , namespace_str + '/tf_static' ),
79- SetRemap ('/scan' , namespace_str + '/scan' ),
80- SetRemap ('/map' , namespace_str + '/map' ),
81- SetRemap ('/map_metadata' , namespace_str + '/map_metadata' ),
8291
8392 IncludeLaunchDescription (
8493 PythonLaunchDescriptionSource (launch_slam_sync ),
8594 launch_arguments = [
8695 ('use_sim_time' , use_sim_time ),
8796 ('autostart' , autostart ),
8897 ('use_lifecycle_manager' , use_lifecycle_manager ),
89- ('slam_params_file' , slam_params )
98+ ('slam_params_file' , rewritten_slam_params )
9099 ],
91100 condition = IfCondition (sync )
92101 ),
@@ -97,7 +106,7 @@ def launch_setup(context, *args, **kwargs):
97106 ('use_sim_time' , use_sim_time ),
98107 ('autostart' , autostart ),
99108 ('use_lifecycle_manager' , use_lifecycle_manager ),
100- ('slam_params_file' , slam_params )
109+ ('slam_params_file' , rewritten_slam_params )
101110 ],
102111 condition = UnlessCondition (sync )
103112 )
0 commit comments