Skip to content

Commit

Permalink
Rename params_file to slam_params_file to avoid name conflicts (Steve…
Browse files Browse the repository at this point in the history
  • Loading branch information
v-lopez authored Mar 13, 2021
1 parent 9af02a7 commit e02f505
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 10 deletions.
10 changes: 5 additions & 5 deletions launch/online_async_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,21 +9,21 @@

def generate_launch_description():
use_sim_time = LaunchConfiguration('use_sim_time')
params_file = LaunchConfiguration('params_file')
slam_params_file = LaunchConfiguration('slam_params_file')

declare_use_sim_time_argument = DeclareLaunchArgument(
'use_sim_time',
default_value='true',
description='Use simulation/Gazebo clock')
declare_params_file_cmd = DeclareLaunchArgument(
'params_file',
declare_slam_params_file_cmd = DeclareLaunchArgument(
'slam_params_file',
default_value=os.path.join(get_package_share_directory("slam_toolbox"),
'config', 'mapper_params_online_async.yaml'),
description='Full path to the ROS2 parameters file to use for the slam_toolbox node')

start_async_slam_toolbox_node = Node(
parameters=[
params_file,
slam_params_file,
{'use_sim_time': use_sim_time}
],
package='slam_toolbox',
Expand All @@ -34,7 +34,7 @@ def generate_launch_description():
ld = LaunchDescription()

ld.add_action(declare_use_sim_time_argument)
ld.add_action(declare_params_file_cmd)
ld.add_action(declare_slam_params_file_cmd)
ld.add_action(start_async_slam_toolbox_node)

return ld
10 changes: 5 additions & 5 deletions launch/online_sync_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,21 +9,21 @@

def generate_launch_description():
use_sim_time = LaunchConfiguration('use_sim_time')
params_file = LaunchConfiguration('params_file')
slam_params_file = LaunchConfiguration('slam_params_file')

declare_use_sim_time_argument = DeclareLaunchArgument(
'use_sim_time',
default_value='true',
description='Use simulation/Gazebo clock')
declare_params_file_cmd = DeclareLaunchArgument(
'params_file',
declare_slam_params_file_cmd = DeclareLaunchArgument(
'slam_params_file',
default_value=os.path.join(get_package_share_directory("slam_toolbox"),
'config', 'mapper_params_online_sync.yaml'),
description='Full path to the ROS2 parameters file to use for the slam_toolbox node')

start_sync_slam_toolbox_node = Node(
parameters=[
params_file,
slam_params_file,
{'use_sim_time': use_sim_time}
],
package='slam_toolbox',
Expand All @@ -34,7 +34,7 @@ def generate_launch_description():
ld = LaunchDescription()

ld.add_action(declare_use_sim_time_argument)
ld.add_action(declare_params_file_cmd)
ld.add_action(declare_slam_params_file_cmd)
ld.add_action(start_sync_slam_toolbox_node)

return ld

0 comments on commit e02f505

Please sign in to comment.