@@ -49,25 +49,17 @@ def generate_launch_description():
4949 * launch_args ,
5050 launch .actions .DeclareLaunchArgument (name = "pose_topic" ,
5151 default_value = "/pose" ),
52+ launch .actions .DeclareLaunchArgument (name = "map_topic" ,
53+ default_value = "/map" ),
5254 launch_ros .actions .Node (
5355 package = 'slam_gmapping' ,
5456 node_executable = 'slam_gmapping' ,
5557 node_name = 'slam_gmapping' , output = 'screen' ,
5658 parameters = [{k : launch .substitutions .LaunchConfiguration (k )
5759 for k , _ in config_vars }],
5860 remappings = [("/pose" ,
59- launch .substitutions .LaunchConfiguration ("pose_topic" ))]
61+ launch .substitutions .LaunchConfiguration ("pose_topic" )),
62+ ("/map" ,
63+ launch .substitutions .LaunchConfiguration ("map_topic" ))]
6064 ),
6165 ])
62-
63-
64- # launch.actions.DeclareLaunchArgument(
65- # 'maxUrange', default_value='false', description='Use simulation (Gazebo) clock if true'),
66-
67- # return LaunchDescription([
68- # launch_ros.actions.Node(
69- # package='slam_gmapping',
70- # node_executable='slam_gmapping',
71- # node_name='slam_gmapping', output='screen',
72- # parameters=[{'maxUrange': maxUrange}]),
73- # ])
0 commit comments