-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathnavigation.launch.py
161 lines (135 loc) · 5.5 KB
/
navigation.launch.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
# -*- coding: utf-8 -*-
# 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.
"""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,
ExecuteProcess,
IncludeLaunchDescription,
)
from launch.conditions import IfCondition
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration, PythonExpression
from launch_ros.actions import Node
def generate_launch_description():
# Get the launch directory
bringup_dir = get_package_share_directory("nav2_bringup")
c300_nav_dir = get_package_share_directory("c300_navigation")
launch_dir = os.path.join(bringup_dir, "launch")
# Create the launch configuration variables
slam = LaunchConfiguration("slam")
namespace = LaunchConfiguration("namespace")
use_namespace = LaunchConfiguration("use_namespace")
map_yaml_file = LaunchConfiguration("map")
use_sim_time = LaunchConfiguration("use_sim_time")
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_rviz = LaunchConfiguration("use_rviz")
# 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_slam_cmd = DeclareLaunchArgument(
"slam", default_value="True", description="Whether run a SLAM"
)
declare_map_yaml_cmd = DeclareLaunchArgument(
"map",
default_value=os.path.join(c300_nav_dir, "map", "house.yaml"),
description="Full path to map file to load",
)
declare_use_sim_time_cmd = DeclareLaunchArgument(
"use_sim_time",
default_value="True",
description="Use simulation (Gazebo) clock if True",
)
declare_params_file_cmd = DeclareLaunchArgument(
"params_file",
default_value=os.path.join(c300_nav_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(c300_nav_dir, "rviz", "navigation.rviz"),
description="Full path to the RVIZ config file to use",
)
declare_use_rviz_cmd = DeclareLaunchArgument(
"use_rviz", default_value="True", description="Whether to start RVIZ"
)
rviz_cmd = IncludeLaunchDescription(
PythonLaunchDescriptionSource(os.path.join(launch_dir, "rviz_launch.py")),
condition=IfCondition(use_rviz),
launch_arguments={
"namespace": namespace,
"use_namespace": use_namespace,
"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,
"slam": slam,
"map": map_yaml_file,
"use_sim_time": use_sim_time,
"params_file": params_file,
"autostart": autostart,
"use_composition": use_composition,
"use_respawn": use_respawn,
}.items(),
)
# 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_slam_cmd)
ld.add_action(declare_map_yaml_cmd)
ld.add_action(declare_use_sim_time_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_rviz_cmd)
ld.add_action(declare_use_respawn_cmd)
ld.add_action(rviz_cmd)
ld.add_action(bringup_cmd)
return ld