ros2aria/husarion_utils/bringup_launch.py

185 lines
7.1 KiB
Python
Raw Normal View History

# Copyright (c) 2018 Intel Corporation
#
# 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.
import os
from launch import LaunchDescription
from launch.actions import (
DeclareLaunchArgument,
GroupAction,
IncludeLaunchDescription,
SetEnvironmentVariable,
OpaqueFunction,
)
from launch.conditions import IfCondition
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import EnvironmentVariable, 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, ReplaceString
def launch_setup(context, *args, **kwargs):
# Get the launch directory
launch_dir = "/husarion_utils"
# Create the launch configuration variables
namespace = LaunchConfiguration("namespace").perform(context)
observation_topic = LaunchConfiguration("observation_topic").perform(context)
map_yaml_file = LaunchConfiguration("map").perform(context)
use_sim_time = LaunchConfiguration("use_sim_time").perform(context)
params_file = LaunchConfiguration("params_file").perform(context)
slam = LaunchConfiguration("slam").perform(context)
autostart = LaunchConfiguration("autostart").perform(context)
use_composition = LaunchConfiguration("use_composition").perform(context)
use_respawn = LaunchConfiguration("use_respawn").perform(context)
log_level = LaunchConfiguration("log_level").perform(context)
# Create our own temporary YAML files that include substitutions
param_substitutions = {"use_sim_time": use_sim_time, "yaml_filename": map_yaml_file}
if namespace:
params_file = ReplaceString(
source_file=params_file, replacements={"<robot_namespace>": namespace}
)
else:
params_file = ReplaceString(
source_file=params_file, replacements={"<robot_namespace>/": ""}
)
params_file = ReplaceString(
source_file=params_file, replacements={"<observation_topic>": observation_topic}
)
configured_params = ParameterFile(
RewrittenYaml(
source_file=params_file,
root_key=namespace,
param_rewrites=param_substitutions,
convert_types=True,
),
allow_substs=True,
)
# Specify the actions
bringup_cmd_group = GroupAction(
[
PushRosNamespace(namespace),
Node(
condition=IfCondition(use_composition),
name="nav2_container",
package="rclcpp_components",
executable="component_container_isolated",
parameters=[configured_params, {"autostart": autostart}],
arguments=["--ros-args", "--log-level", log_level],
output="screen",
),
IncludeLaunchDescription(
PythonLaunchDescriptionSource(os.path.join(launch_dir, "slam_launch.py")),
condition=IfCondition(slam),
launch_arguments={
"namespace": namespace,
"use_sim_time": use_sim_time,
"autostart": autostart,
"use_respawn": use_respawn,
"params_file": params_file,
}.items(),
),
IncludeLaunchDescription(
PythonLaunchDescriptionSource(os.path.join(launch_dir, "localization_launch.py")),
condition=IfCondition(PythonExpression(["not ", slam])),
launch_arguments={
"namespace": namespace,
"map": map_yaml_file,
"use_sim_time": use_sim_time,
"autostart": autostart,
"params_file": params_file,
"use_composition": use_composition,
"use_respawn": use_respawn,
"container_name": "nav2_container",
}.items(),
),
IncludeLaunchDescription(
PythonLaunchDescriptionSource(os.path.join(launch_dir, "navigation_launch.py")),
launch_arguments={
"namespace": namespace,
"use_sim_time": use_sim_time,
"autostart": autostart,
"params_file": params_file,
"use_composition": use_composition,
"use_respawn": use_respawn,
"container_name": "nav2_container",
}.items(),
),
]
)
healthcheck_node = Node(
package="healthcheck_pkg",
executable="healthcheck_node",
name="healthcheck_navigation",
namespace=namespace,
output="screen",
)
return [bringup_cmd_group, healthcheck_node]
def generate_launch_description():
return LaunchDescription(
[
SetEnvironmentVariable("RCUTILS_LOGGING_BUFFERED_STREAM", "1"),
DeclareLaunchArgument(
"namespace",
default_value=EnvironmentVariable("ROBOT_NAMESPACE", default_value=""),
description="Top-level namespace",
),
DeclareLaunchArgument(
"observation_topic",
default_value="",
description="Topic name for PointCloud2 messages.",
),
DeclareLaunchArgument("slam", default_value="False", description="Whether run a SLAM"),
DeclareLaunchArgument("map", description="Full path to map yaml file to load"),
DeclareLaunchArgument(
"use_sim_time",
default_value="false",
description="Use simulation (Gazebo) clock if true",
),
DeclareLaunchArgument(
"params_file",
default_value=os.path.join("/params.yaml"),
description="Full path to the ROS2 parameters file to use for all launched nodes",
),
DeclareLaunchArgument(
"autostart",
default_value="true",
description="Automatically startup the nav2 stack",
),
DeclareLaunchArgument(
"use_composition",
default_value="True",
description="Whether to use composed bringup",
),
DeclareLaunchArgument(
"use_respawn",
default_value="False",
description="Whether to respawn if a node crashes. Applied when composition is disabled.",
),
DeclareLaunchArgument("log_level", default_value="info", description="log level"),
OpaqueFunction(function=launch_setup),
]
)