Skip to content

Commit

Permalink
Adding new Nav2 loopback simulator (#4614)
Browse files Browse the repository at this point in the history
* adding Nav2 loopback sim

Signed-off-by: Steve Macenski <[email protected]>

* drop performance by half

* lintin

* Add multirobot usecase comment

* fixing copy paste error

* fixing review comments

---------

Signed-off-by: Steve Macenski <[email protected]>
  • Loading branch information
SteveMacenski authored Aug 12, 2024
1 parent 5321e00 commit 3f31112
Show file tree
Hide file tree
Showing 16 changed files with 996 additions and 2 deletions.
11 changes: 9 additions & 2 deletions nav2_bringup/launch/bringup_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@ def generate_launch_description():
use_composition = LaunchConfiguration('use_composition')
use_respawn = LaunchConfiguration('use_respawn')
log_level = LaunchConfiguration('log_level')
use_localization = LaunchConfiguration('use_localization')

# Map fully qualified names to relative ones so the node's namespace can be prepended.
# In case of the transforms (tf), currently, there doesn't seem to be a better alternative
Expand Down Expand Up @@ -99,6 +100,11 @@ def generate_launch_description():
'map', default_value='', description='Full path to map yaml file to load'
)

declare_use_localization_cmd = DeclareLaunchArgument(
'use_localization', default_value='True',
description='Whether to enable localization or not'
)

declare_use_sim_time_cmd = DeclareLaunchArgument(
'use_sim_time',
default_value='false',
Expand Down Expand Up @@ -151,7 +157,7 @@ def generate_launch_description():
PythonLaunchDescriptionSource(
os.path.join(launch_dir, 'slam_launch.py')
),
condition=IfCondition(slam),
condition=IfCondition(PythonExpression([slam, ' and ', use_localization])),
launch_arguments={
'namespace': namespace,
'use_sim_time': use_sim_time,
Expand All @@ -164,7 +170,7 @@ def generate_launch_description():
PythonLaunchDescriptionSource(
os.path.join(launch_dir, 'localization_launch.py')
),
condition=IfCondition(PythonExpression(['not ', slam])),
condition=IfCondition(PythonExpression(['not ', slam, ' and ', use_localization])),
launch_arguments={
'namespace': namespace,
'map': map_yaml_file,
Expand Down Expand Up @@ -210,6 +216,7 @@ def generate_launch_description():
ld.add_action(declare_use_composition_cmd)
ld.add_action(declare_use_respawn_cmd)
ld.add_action(declare_log_level_cmd)
ld.add_action(declare_use_localization_cmd)

# Add the actions to launch all of the navigation nodes
ld.add_action(bringup_cmd_group)
Expand Down
224 changes: 224 additions & 0 deletions nav2_bringup/launch/tb3_loopback_simulation.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,224 @@
# Copyright (C) 2024 Open Navigation LLC
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

"""This is all-in-one launch script intended for use by nav2 developers."""

import os

from ament_index_python.packages import get_package_share_directory

from launch import LaunchDescription
from launch.actions import (
DeclareLaunchArgument,
GroupAction,
IncludeLaunchDescription,
)
from launch.conditions import IfCondition
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node, SetParameter
from launch_ros.descriptions import ParameterFile

from nav2_common.launch import RewrittenYaml


def generate_launch_description():
# Get the launch directory
bringup_dir = get_package_share_directory('nav2_bringup')
loopback_sim_dir = get_package_share_directory('nav2_loopback_sim')
launch_dir = os.path.join(bringup_dir, 'launch')
sim_dir = get_package_share_directory('nav2_minimal_tb3_sim')

# Create the launch configuration variables
namespace = LaunchConfiguration('namespace')
use_namespace = LaunchConfiguration('use_namespace')
map_yaml_file = LaunchConfiguration('map')
params_file = LaunchConfiguration('params_file')
autostart = LaunchConfiguration('autostart')
use_composition = LaunchConfiguration('use_composition')
use_respawn = LaunchConfiguration('use_respawn')

# Launch configuration variables specific to simulation
rviz_config_file = LaunchConfiguration('rviz_config_file')
use_robot_state_pub = LaunchConfiguration('use_robot_state_pub')
use_rviz = LaunchConfiguration('use_rviz')

remappings = [('/tf', 'tf'), ('/tf_static', 'tf_static')]

# Declare the launch arguments
declare_namespace_cmd = DeclareLaunchArgument(
'namespace', default_value='', description='Top-level namespace'
)

declare_use_namespace_cmd = DeclareLaunchArgument(
'use_namespace',
default_value='false',
description='Whether to apply a namespace to the navigation stack',
)

declare_map_yaml_cmd = DeclareLaunchArgument(
'map',
default_value=os.path.join(bringup_dir, 'maps', 'tb3_sandbox.yaml'),
)

declare_params_file_cmd = DeclareLaunchArgument(
'params_file',
default_value=os.path.join(bringup_dir, 'params', 'nav2_params.yaml'),
description='Full path to the ROS2 parameters file to use for all launched nodes',
)

declare_autostart_cmd = DeclareLaunchArgument(
'autostart',
default_value='true',
description='Automatically startup the nav2 stack',
)

declare_use_composition_cmd = DeclareLaunchArgument(
'use_composition',
default_value='True',
description='Whether to use composed bringup',
)

declare_use_respawn_cmd = DeclareLaunchArgument(
'use_respawn',
default_value='False',
description='Whether to respawn if a node crashes. Applied when composition is disabled.',
)

declare_rviz_config_file_cmd = DeclareLaunchArgument(
'rviz_config_file',
default_value=os.path.join(bringup_dir, 'rviz', 'nav2_default_view.rviz'),
description='Full path to the RVIZ config file to use',
)

declare_use_robot_state_pub_cmd = DeclareLaunchArgument(
'use_robot_state_pub',
default_value='True',
description='Whether to start the robot state publisher',
)

declare_use_rviz_cmd = DeclareLaunchArgument(
'use_rviz', default_value='True', description='Whether to start RVIZ'
)

urdf = os.path.join(sim_dir, 'urdf', 'turtlebot3_waffle.urdf')
with open(urdf, 'r') as infp:
robot_description = infp.read()

start_robot_state_publisher_cmd = Node(
condition=IfCondition(use_robot_state_pub),
package='robot_state_publisher',
executable='robot_state_publisher',
name='robot_state_publisher',
namespace=namespace,
output='screen',
parameters=[
{'use_sim_time': True, 'robot_description': robot_description}
],
remappings=remappings,
)

rviz_cmd = IncludeLaunchDescription(
PythonLaunchDescriptionSource(os.path.join(launch_dir, 'rviz_launch.py')),
condition=IfCondition(use_rviz),
launch_arguments={
'namespace': namespace,
'use_namespace': use_namespace,
'use_sim_time': 'True',
'rviz_config': rviz_config_file,
}.items(),
)

bringup_cmd = IncludeLaunchDescription(
PythonLaunchDescriptionSource(os.path.join(launch_dir, 'bringup_launch.py')),
launch_arguments={
'namespace': namespace,
'use_namespace': use_namespace,
'map': map_yaml_file,
'use_sim_time': 'True',
'params_file': params_file,
'autostart': autostart,
'use_composition': use_composition,
'use_respawn': use_respawn,
'use_localization': 'False', # Don't use SLAM, AMCL
}.items(),
)

loopback_sim_cmd = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(loopback_sim_dir, 'loopback_simulation.launch.py')),
launch_arguments={
'params_file': params_file,
}.items(),
)

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

start_map_server = GroupAction(
actions=[
SetParameter('use_sim_time', True),
Node(
package='nav2_map_server',
executable='map_server',
name='map_server',
output='screen',
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params, {'yaml_filename': map_yaml_file}],
remappings=remappings,
),
Node(
package='nav2_lifecycle_manager',
executable='lifecycle_manager',
name='lifecycle_manager_map_server',
output='screen',
parameters=[
configured_params,
{'autostart': autostart}, {'node_names': ['map_server']}],
),
]
)

# Create the launch description and populate
ld = LaunchDescription()

# Declare the launch options
ld.add_action(declare_namespace_cmd)
ld.add_action(declare_use_namespace_cmd)
ld.add_action(declare_map_yaml_cmd)
ld.add_action(declare_params_file_cmd)
ld.add_action(declare_autostart_cmd)
ld.add_action(declare_use_composition_cmd)

ld.add_action(declare_rviz_config_file_cmd)
ld.add_action(declare_use_robot_state_pub_cmd)
ld.add_action(declare_use_rviz_cmd)
ld.add_action(declare_use_respawn_cmd)

# Add the actions to launch all of the navigation nodes
ld.add_action(start_robot_state_publisher_cmd)
ld.add_action(start_map_server)
ld.add_action(loopback_sim_cmd)
ld.add_action(rviz_cmd)
ld.add_action(bringup_cmd)

return ld
Loading

0 comments on commit 3f31112

Please sign in to comment.