Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions turtlebot4_navigation/config/slam.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@ slam_toolbox:
# ROS Parameters
odom_frame: odom
map_frame: map
map_name: /map
base_frame: base_link
scan_topic: /scan
use_map_saver: true
Expand Down
19 changes: 14 additions & 5 deletions turtlebot4_navigation/launch/slam.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,8 @@
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
from launch_ros.actions import PushRosNamespace, SetRemap

from nav2_common.launch import RewrittenYaml

pkg_turtlebot4_navigation = get_package_share_directory('turtlebot4_navigation')
pkg_slam_toolbox = get_package_share_directory('slam_toolbox')

Expand Down Expand Up @@ -71,22 +73,29 @@ def launch_setup(context, *args, **kwargs):
launch_slam_async = PathJoinSubstitution(
[pkg_slam_toolbox, 'launch', 'online_async_launch.py'])

rewritten_slam_params = RewrittenYaml(
source_file=slam_params,
root_key=namespace_str,
param_rewrites={
'map_name': namespace_str + '/map',
'scan_topic': namespace_str + '/scan',
},
convert_types=True,
)

slam = GroupAction([
PushRosNamespace(namespace),

SetRemap('/tf', namespace_str + '/tf'),
SetRemap('/tf_static', namespace_str + '/tf_static'),
SetRemap('/scan', namespace_str + '/scan'),
SetRemap('/map', namespace_str + '/map'),
SetRemap('/map_metadata', namespace_str + '/map_metadata'),

IncludeLaunchDescription(
PythonLaunchDescriptionSource(launch_slam_sync),
launch_arguments=[
('use_sim_time', use_sim_time),
('autostart', autostart),
('use_lifecycle_manager', use_lifecycle_manager),
('slam_params_file', slam_params)
('slam_params_file', rewritten_slam_params)
],
condition=IfCondition(sync)
),
Expand All @@ -97,7 +106,7 @@ def launch_setup(context, *args, **kwargs):
('use_sim_time', use_sim_time),
('autostart', autostart),
('use_lifecycle_manager', use_lifecycle_manager),
('slam_params_file', slam_params)
('slam_params_file', rewritten_slam_params)
],
condition=UnlessCondition(sync)
)
Expand Down
Loading