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
13 changes: 8 additions & 5 deletions nav2_bringup/launch/bringup_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
from launch.substitutions import LaunchConfiguration, PythonExpression
from launch_ros.actions import Node
from launch_ros.actions import PushRosNamespace
from launch_ros.descriptions import ParameterFile
from nav2_common.launch import RewrittenYaml


Expand Down Expand Up @@ -58,11 +59,13 @@ def generate_launch_description():
'use_sim_time': use_sim_time,
'yaml_filename': map_yaml_file}

configured_params = RewrittenYaml(
source_file=params_file,
root_key=namespace,
param_rewrites=param_substitutions,
convert_types=True)
configured_params = ParameterFile(
RewrittenYaml(
source_file=params_file,
root_key=namespace,
param_rewrites=param_substitutions,
convert_types=True),
allow_substs=True)

stdout_linebuf_envvar = SetEnvironmentVariable(
'RCUTILS_LOGGING_BUFFERED_STREAM', '1')
Expand Down
14 changes: 8 additions & 6 deletions nav2_bringup/launch/localization_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
from launch.substitutions import LaunchConfiguration, PythonExpression
from launch_ros.actions import LoadComposableNodes
from launch_ros.actions import Node
from launch_ros.descriptions import ComposableNode
from launch_ros.descriptions import ComposableNode, ParameterFile
from nav2_common.launch import RewrittenYaml


Expand Down Expand Up @@ -57,11 +57,13 @@ def generate_launch_description():
'use_sim_time': use_sim_time,
'yaml_filename': map_yaml_file}

configured_params = RewrittenYaml(
source_file=params_file,
root_key=namespace,
param_rewrites=param_substitutions,
convert_types=True)
configured_params = ParameterFile(
RewrittenYaml(
source_file=params_file,
root_key=namespace,
param_rewrites=param_substitutions,
convert_types=True),
allow_substs=True)

stdout_linebuf_envvar = SetEnvironmentVariable(
'RCUTILS_LOGGING_BUFFERED_STREAM', '1')
Expand Down
8 changes: 5 additions & 3 deletions nav2_bringup/launch/navigation_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
from launch.substitutions import LaunchConfiguration, PythonExpression
from launch_ros.actions import LoadComposableNodes
from launch_ros.actions import Node
from launch_ros.descriptions import ComposableNode
from launch_ros.descriptions import ComposableNode, ParameterFile
from nav2_common.launch import RewrittenYaml


Expand Down Expand Up @@ -62,11 +62,13 @@ def generate_launch_description():
'use_sim_time': use_sim_time,
'autostart': autostart}

configured_params = RewrittenYaml(
configured_params = ParameterFile(
RewrittenYaml(
source_file=params_file,
root_key=namespace,
param_rewrites=param_substitutions,
convert_types=True)
convert_types=True),
allow_substs=True)

stdout_linebuf_envvar = SetEnvironmentVariable(
'RCUTILS_LOGGING_BUFFERED_STREAM', '1')
Expand Down
13 changes: 8 additions & 5 deletions nav2_bringup/launch/slam_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
from launch_ros.descriptions import ParameterFile
from nav2_common.launch import HasNodeParams, RewrittenYaml


Expand All @@ -46,11 +47,13 @@ def generate_launch_description():
param_substitutions = {
'use_sim_time': use_sim_time}

configured_params = RewrittenYaml(
source_file=params_file,
root_key=namespace,
param_rewrites=param_substitutions,
convert_types=True)
configured_params = ParameterFile(
RewrittenYaml(
source_file=params_file,
root_key=namespace,
param_rewrites=param_substitutions,
convert_types=True),
allow_substs=True)

# Declare the launch arguments
declare_namespace_cmd = DeclareLaunchArgument(
Expand Down
13 changes: 8 additions & 5 deletions nav2_collision_monitor/launch/collision_monitor_node.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
from launch_ros.descriptions import ParameterFile
from nav2_common.launch import RewrittenYaml


Expand Down Expand Up @@ -59,11 +60,13 @@ def generate_launch_description():
param_substitutions = {
'use_sim_time': use_sim_time}

configured_params = RewrittenYaml(
source_file=params_file,
root_key=namespace,
param_rewrites=param_substitutions,
convert_types=True)
configured_params = ParameterFile(
RewrittenYaml(
source_file=params_file,
root_key=namespace,
param_rewrites=param_substitutions,
convert_types=True),
allow_substs=True)

# Nodes launching commands
start_lifecycle_manager_cmd = Node(
Expand Down