Skip to content

Commit 3741063

Browse files
SteveMacenskiIbrahim Özcan
authored andcommitted
* changed slam launch file according to the comments for the PR ros-navigation#4211 Signed-off-by: Ibrahim Özcan <[email protected]> * Fixing litning problems --------- Signed-off-by: Ibrahim Özcan <[email protected]> Co-authored-by: Ibrahim Özcan <[email protected]>
1 parent a3c6eea commit 3741063

File tree

1 file changed

+22
-15
lines changed

1 file changed

+22
-15
lines changed

nav2_bringup/launch/slam_launch.py

Lines changed: 22 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121
from launch.conditions import IfCondition, UnlessCondition
2222
from launch.launch_description_sources import PythonLaunchDescriptionSource
2323
from launch.substitutions import LaunchConfiguration
24-
from launch_ros.actions import Node, SetParameter
24+
from launch_ros.actions import Node, SetParameter, SetRemap
2525
from launch_ros.descriptions import ParameterFile
2626
from nav2_common.launch import HasNodeParams, RewrittenYaml
2727

@@ -88,7 +88,6 @@ def generate_launch_description():
8888
)
8989

9090
# Nodes launching commands
91-
9291
start_map_server = GroupAction(
9392
actions=[
9493
SetParameter('use_sim_time', use_sim_time),
@@ -119,19 +118,28 @@ def generate_launch_description():
119118
source_file=params_file, node_name='slam_toolbox'
120119
)
121120

122-
start_slam_toolbox_cmd = IncludeLaunchDescription(
123-
PythonLaunchDescriptionSource(slam_launch_file),
124-
launch_arguments={'use_sim_time': use_sim_time}.items(),
125-
condition=UnlessCondition(has_slam_toolbox_params),
126-
)
121+
start_slam_toolbox_cmd = GroupAction(
122+
123+
actions=[
124+
# Remapping required to have a slam session subscribe & publish in optional namespaces
125+
SetRemap(src='/scan', dst='scan'),
126+
SetRemap(src='/tf', dst='tf'),
127+
SetRemap(src='/tf_static', dst='tf_static'),
128+
SetRemap(src='/map', dst='map'),
129+
130+
IncludeLaunchDescription(
131+
PythonLaunchDescriptionSource(slam_launch_file),
132+
launch_arguments={'use_sim_time': use_sim_time}.items(),
133+
condition=UnlessCondition(has_slam_toolbox_params),
134+
),
127135

128-
start_slam_toolbox_cmd_with_params = IncludeLaunchDescription(
129-
PythonLaunchDescriptionSource(slam_launch_file),
130-
launch_arguments={
131-
'use_sim_time': use_sim_time,
132-
'slam_params_file': params_file,
133-
}.items(),
134-
condition=IfCondition(has_slam_toolbox_params),
136+
IncludeLaunchDescription(
137+
PythonLaunchDescriptionSource(slam_launch_file),
138+
launch_arguments={'use_sim_time': use_sim_time,
139+
'slam_params_file': params_file}.items(),
140+
condition=IfCondition(has_slam_toolbox_params),
141+
)
142+
]
135143
)
136144

137145
ld = LaunchDescription()
@@ -149,6 +157,5 @@ def generate_launch_description():
149157

150158
# Running SLAM Toolbox (Only one of them will be run)
151159
ld.add_action(start_slam_toolbox_cmd)
152-
ld.add_action(start_slam_toolbox_cmd_with_params)
153160

154161
return ld

0 commit comments

Comments
 (0)