Skip to content
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,9 @@ bool BtActionServer<ActionT>::on_configure()
"-r",
std::string("__node:=") +
std::string(node->get_name()) + "_" + client_node_name + "_rclcpp_node",
"-p",
"use_sim_time:=" +
std::string(node->get_parameter("use_sim_time").as_bool() ? "true" : "false"),
"--"});

// Support for handling the topic-based goal pose from rviz
Expand Down
1 change: 0 additions & 1 deletion nav2_bringup/launch/bringup_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,6 @@ def generate_launch_description():

# Create our own temporary YAML files that include substitutions
param_substitutions = {
'use_sim_time': use_sim_time,
'yaml_filename': map_yaml_file}

configured_params = RewrittenYaml(
Expand Down
59 changes: 31 additions & 28 deletions nav2_bringup/launch/localization_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
from launch.actions import DeclareLaunchArgument, GroupAction, SetEnvironmentVariable
from launch.conditions import IfCondition
from launch.substitutions import LaunchConfiguration, PythonExpression
from launch_ros.actions import LoadComposableNodes
from launch_ros.actions import LoadComposableNodes, SetParameter
from launch_ros.actions import Node
from launch_ros.descriptions import ComposableNode
from nav2_common.launch import RewrittenYaml
Expand Down Expand Up @@ -52,7 +52,6 @@ def generate_launch_description():

# Create our own temporary YAML files that include substitutions
param_substitutions = {
'use_sim_time': use_sim_time,
'yaml_filename': map_yaml_file}

configured_params = RewrittenYaml(
Expand Down Expand Up @@ -102,6 +101,7 @@ def generate_launch_description():
load_nodes = GroupAction(
condition=IfCondition(PythonExpression(['not ', use_composition])),
actions=[
SetParameter("use_sim_time", use_sim_time),
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

does SetParameter work globally or can it be used for a single node? Also, does that work if the parameter in question is inside of the yaml file also (clearly it works if its not inside the yaml file)? I ask because this could be a really nice solution for the yaml_filename thing too if we can set it for only the map server if there is a non-trivial value set in the launch configuration.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It would be great not to require users to set yaml_filename in the yaml if we're going to override it always in launch using the CLI or the launch configuration defaults. This could be that solution, as long as it works if the parameter is in the yaml file too.

In general though, that's a problem with this PR if it doesn't work with the param in the yaml too, since users' yaml files right now will have it from previous clones they're working under

Copy link
Contributor Author

@tonynajjar tonynajjar Aug 22, 2022

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

does SetParameter work globally or can it be used for a single node?

It applies the parameter for all nodes within the GroupAction. See here

Also, does that work if the parameter in question is inside of the yaml file also

yes, the parameter in the yaml would override

For the refactoring of yaml_filename, I'd prefer if we can open a separate issue. I might take it but can't commit to it right now

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Totally understood, just asking the question, it sounds like this would be a solution for it too. Duly noted.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Leaving this un-resolved as a reminder to myself

Node(
package='nav2_map_server',
executable='map_server',
Expand All @@ -125,37 +125,40 @@ def generate_launch_description():
executable='lifecycle_manager',
name='lifecycle_manager_localization',
output='screen',
parameters=[{'use_sim_time': use_sim_time},
{'autostart': autostart},
parameters=[{'autostart': autostart},
{'node_names': lifecycle_nodes}])
]
)

load_composable_nodes = LoadComposableNodes(
load_composable_nodes = GroupAction(
condition=IfCondition(use_composition),
target_container=container_name,
composable_node_descriptions=[
ComposableNode(
package='nav2_map_server',
plugin='nav2_map_server::MapServer',
name='map_server',
parameters=[configured_params],
remappings=remappings),
ComposableNode(
package='nav2_amcl',
plugin='nav2_amcl::AmclNode',
name='amcl',
parameters=[configured_params],
remappings=remappings),
ComposableNode(
package='nav2_lifecycle_manager',
plugin='nav2_lifecycle_manager::LifecycleManager',
name='lifecycle_manager_localization',
parameters=[{'use_sim_time': use_sim_time,
'autostart': autostart,
'node_names': lifecycle_nodes}]),
],
)
actions=[
SetParameter("use_sim_time", use_sim_time),
LoadComposableNodes(
target_container=container_name,
composable_node_descriptions=[
ComposableNode(
package='nav2_map_server',
plugin='nav2_map_server::MapServer',
name='map_server',
parameters=[configured_params],
remappings=remappings),
ComposableNode(
package='nav2_amcl',
plugin='nav2_amcl::AmclNode',
name='amcl',
parameters=[configured_params],
remappings=remappings),
ComposableNode(
package='nav2_lifecycle_manager',
plugin='nav2_lifecycle_manager::LifecycleManager',
name='lifecycle_manager_localization',
parameters=[{'autostart': autostart,
'node_names': lifecycle_nodes}]),
],
)
]
)

# Create the launch description and populate
ld = LaunchDescription()
Expand Down
118 changes: 59 additions & 59 deletions nav2_bringup/launch/navigation_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
from launch.actions import DeclareLaunchArgument, GroupAction, SetEnvironmentVariable
from launch.conditions import IfCondition
from launch.substitutions import LaunchConfiguration, PythonExpression
from launch_ros.actions import LoadComposableNodes
from launch_ros.actions import LoadComposableNodes, SetParameter
from launch_ros.actions import Node
from launch_ros.descriptions import ComposableNode
from nav2_common.launch import RewrittenYaml
Expand Down Expand Up @@ -57,7 +57,6 @@ def generate_launch_description():

# Create our own temporary YAML files that include substitutions
param_substitutions = {
'use_sim_time': use_sim_time,
'autostart': autostart}

configured_params = RewrittenYaml(
Expand Down Expand Up @@ -103,6 +102,7 @@ def generate_launch_description():
load_nodes = GroupAction(
condition=IfCondition(PythonExpression(['not ', use_composition])),
actions=[
SetParameter("use_sim_time", use_sim_time),
Node(
package='nav2_controller',
executable='controller_server',
Expand Down Expand Up @@ -171,68 +171,68 @@ def generate_launch_description():
executable='lifecycle_manager',
name='lifecycle_manager_navigation',
output='screen',
parameters=[{'use_sim_time': use_sim_time},
{'autostart': autostart},
parameters=[{'autostart': autostart},
{'node_names': lifecycle_nodes}]),
]
)

load_composable_nodes = LoadComposableNodes(
load_composable_nodes = GroupAction(
condition=IfCondition(use_composition),
target_container=container_name,
composable_node_descriptions=[
ComposableNode(
package='nav2_controller',
plugin='nav2_controller::ControllerServer',
name='controller_server',
parameters=[configured_params],
remappings=remappings + [('cmd_vel', 'cmd_vel_nav')]),
ComposableNode(
package='nav2_smoother',
plugin='nav2_smoother::SmootherServer',
name='smoother_server',
parameters=[configured_params],
remappings=remappings),
ComposableNode(
package='nav2_planner',
plugin='nav2_planner::PlannerServer',
name='planner_server',
parameters=[configured_params],
remappings=remappings),
ComposableNode(
package='nav2_behaviors',
plugin='behavior_server::BehaviorServer',
name='behavior_server',
parameters=[configured_params],
remappings=remappings),
ComposableNode(
package='nav2_bt_navigator',
plugin='nav2_bt_navigator::BtNavigator',
name='bt_navigator',
parameters=[configured_params],
remappings=remappings),
ComposableNode(
package='nav2_waypoint_follower',
plugin='nav2_waypoint_follower::WaypointFollower',
name='waypoint_follower',
parameters=[configured_params],
remappings=remappings),
ComposableNode(
package='nav2_velocity_smoother',
plugin='nav2_velocity_smoother::VelocitySmoother',
name='velocity_smoother',
parameters=[configured_params],
remappings=remappings +
[('cmd_vel', 'cmd_vel_nav'), ('cmd_vel_smoothed', 'cmd_vel')]),
ComposableNode(
package='nav2_lifecycle_manager',
plugin='nav2_lifecycle_manager::LifecycleManager',
name='lifecycle_manager_navigation',
parameters=[{'use_sim_time': use_sim_time,
'autostart': autostart,
'node_names': lifecycle_nodes}]),
],
)
actions=[SetParameter("use_sim_time", use_sim_time),
LoadComposableNodes(
target_container=container_name,
composable_node_descriptions=[
ComposableNode(
package='nav2_controller',
plugin='nav2_controller::ControllerServer',
name='controller_server',
parameters=[configured_params],
remappings=remappings + [('cmd_vel', 'cmd_vel_nav')]),
ComposableNode(
package='nav2_smoother',
plugin='nav2_smoother::SmootherServer',
name='smoother_server',
parameters=[configured_params],
remappings=remappings),
ComposableNode(
package='nav2_planner',
plugin='nav2_planner::PlannerServer',
name='planner_server',
parameters=[configured_params],
remappings=remappings),
ComposableNode(
package='nav2_behaviors',
plugin='behavior_server::BehaviorServer',
name='behavior_server',
parameters=[configured_params],
remappings=remappings),
ComposableNode(
package='nav2_bt_navigator',
plugin='nav2_bt_navigator::BtNavigator',
name='bt_navigator',
parameters=[configured_params],
remappings=remappings),
ComposableNode(
package='nav2_waypoint_follower',
plugin='nav2_waypoint_follower::WaypointFollower',
name='waypoint_follower',
parameters=[configured_params],
remappings=remappings),
ComposableNode(
package='nav2_velocity_smoother',
plugin='nav2_velocity_smoother::VelocitySmoother',
name='velocity_smoother',
parameters=[configured_params],
remappings=remappings +
[('cmd_vel', 'cmd_vel_nav'), ('cmd_vel_smoothed', 'cmd_vel')]),
ComposableNode(
package='nav2_lifecycle_manager',
plugin='nav2_lifecycle_manager::LifecycleManager',
name='lifecycle_manager_navigation',
parameters=[{'autostart': autostart,
'node_names': lifecycle_nodes}]),
],
)])

# Create the launch description and populate
ld = LaunchDescription()
Expand Down
24 changes: 10 additions & 14 deletions nav2_bringup/launch/slam_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,11 +17,11 @@
from ament_index_python.packages import get_package_share_directory

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, GroupAction
from launch.conditions import IfCondition, UnlessCondition
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
from launch_ros.actions import Node, SetParameter
from nav2_common.launch import HasNodeParams, RewrittenYaml


Expand All @@ -42,13 +42,10 @@ def generate_launch_description():
slam_launch_file = os.path.join(slam_toolbox_dir, 'launch', 'online_sync_launch.py')

# Create our own temporary YAML files that include substitutions
param_substitutions = {
'use_sim_time': use_sim_time}

configured_params = RewrittenYaml(
source_file=params_file,
root_key=namespace,
param_rewrites=param_substitutions,
param_rewrites={},
convert_types=True)

# Declare the launch arguments
Expand Down Expand Up @@ -77,22 +74,22 @@ def generate_launch_description():

# Nodes launching commands

start_map_saver_server_cmd = Node(
start_map_server = GroupAction(
actions=[SetParameter("use_sim_time", use_sim_time), Node(
package='nav2_map_server',
executable='map_saver_server',
output='screen',
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params])

start_lifecycle_manager_cmd = Node(
parameters=[configured_params]),
Node(
package='nav2_lifecycle_manager',
executable='lifecycle_manager',
name='lifecycle_manager_slam',
output='screen',
parameters=[{'use_sim_time': use_sim_time},
{'autostart': autostart},
parameters=[{'autostart': autostart},
{'node_names': lifecycle_nodes}])
])

# If the provided param file doesn't have slam_toolbox params, we must remove the 'params_file'
# LaunchConfiguration, or it will be passed automatically to slam_toolbox and will not load
Expand Down Expand Up @@ -121,8 +118,7 @@ def generate_launch_description():
ld.add_action(declare_use_respawn_cmd)

# Running Map Saver Server
ld.add_action(start_map_saver_server_cmd)
ld.add_action(start_lifecycle_manager_cmd)
ld.add_action(start_map_server)

# Running SLAM Toolbox (Only one of them will be run)
ld.add_action(start_slam_toolbox_cmd)
Expand Down
Loading