forked from autowarefoundation/autoware_launch
-
Notifications
You must be signed in to change notification settings - Fork 3
/
control.launch.py
384 lines (359 loc) · 16.3 KB
/
control.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
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
# Copyright 2020 Tier IV, Inc. All rights reserved.
#
# 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 launch
from launch.actions import DeclareLaunchArgument
from launch.actions import GroupAction
from launch.actions import IncludeLaunchDescription
from launch.actions import OpaqueFunction
from launch.actions import SetLaunchConfiguration
from launch.conditions import IfCondition
from launch.conditions import LaunchConfigurationEquals
from launch.conditions import UnlessCondition
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import ComposableNodeContainer
from launch_ros.actions import LoadComposableNodes
from launch_ros.actions import PushRosNamespace
from launch_ros.descriptions import ComposableNode
from launch_ros.substitutions import FindPackageShare
import yaml
def launch_setup(context, *args, **kwargs):
lateral_controller_mode = LaunchConfiguration("lateral_controller_mode").perform(context)
if lateral_controller_mode == "mpc_follower":
lat_controller_param_path = (
FindPackageShare("control_launch").perform(context)
+ "/config/trajectory_follower/lateral_controller.param.yaml"
)
with open(lat_controller_param_path, "r") as f:
lat_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"]
elif lateral_controller_mode == "pure_pursuit":
lat_controller_param_path = (
FindPackageShare("control_launch").perform(context)
+ "/config/pure_pursuit/pure_pursuit.param.yaml"
)
with open(lat_controller_param_path, "r") as f:
lat_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"]
lon_controller_param_path = LaunchConfiguration("lon_controller_param_path").perform(context)
with open(lon_controller_param_path, "r") as f:
lon_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"]
latlon_muxer_param_path = LaunchConfiguration("latlon_muxer_param_path").perform(context)
with open(latlon_muxer_param_path, "r") as f:
latlon_muxer_param = yaml.safe_load(f)["/**"]["ros__parameters"]
vehicle_cmd_gate_param_path = LaunchConfiguration("vehicle_cmd_gate_param_path").perform(
context
)
with open(vehicle_cmd_gate_param_path, "r") as f:
vehicle_cmd_gate_param = yaml.safe_load(f)["/**"]["ros__parameters"]
lane_departure_checker_param_path = LaunchConfiguration(
"lane_departure_checker_param_path"
).perform(context)
with open(lane_departure_checker_param_path, "r") as f:
lane_departure_checker_param = yaml.safe_load(f)["/**"]["ros__parameters"]
# lateral controller
mpc_follower_component = ComposableNode(
package="trajectory_follower_nodes",
plugin="autoware::motion::control::trajectory_follower_nodes::LateralController",
name="lateral_controller_node_exe",
namespace="trajectory_follower",
remappings=[
("~/input/reference_trajectory", "/planning/scenario_planning/trajectory"),
("~/input/current_odometry", "/localization/kinematic_state"),
("~/input/current_steering", "/vehicle/status/steering_status"),
("~/output/control_cmd", "lateral/control_cmd"),
("~/output/predicted_trajectory", "lateral/predicted_trajectory"),
("~/output/diagnostic", "lateral/diagnostic"),
],
parameters=[
lat_controller_param,
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
pure_pursuit_component = ComposableNode(
package="pure_pursuit",
plugin="pure_pursuit::PurePursuitNode",
name="pure_pursuit_node_exe",
namespace="trajectory_follower",
remappings=[
("input/reference_trajectory", "/planning/scenario_planning/trajectory"),
("input/current_odometry", "/localization/kinematic_state"),
("output/control_raw", "lateral/control_cmd"),
],
parameters=[
lat_controller_param,
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
# longitudinal controller
lon_controller_component = ComposableNode(
package="trajectory_follower_nodes",
plugin="autoware::motion::control::trajectory_follower_nodes::LongitudinalController",
name="longitudinal_controller_node_exe",
namespace="trajectory_follower",
remappings=[
("~/input/current_trajectory", "/planning/scenario_planning/trajectory"),
("~/input/current_odometry", "/localization/kinematic_state"),
("~/output/control_cmd", "longitudinal/control_cmd"),
("~/output/slope_angle", "longitudinal/slope_angle"),
("~/output/diagnostic", "longitudinal/diagnostic"),
],
parameters=[
lon_controller_param,
{
"control_rate": LaunchConfiguration("control_rate"),
"show_debug_info": LaunchConfiguration("show_debug_info"),
"enable_smooth_stop": LaunchConfiguration("enable_smooth_stop"),
"enable_pub_debug": LaunchConfiguration("enable_pub_debug"),
},
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
# latlon muxer
latlon_muxer_component = ComposableNode(
package="trajectory_follower_nodes",
plugin="autoware::motion::control::trajectory_follower_nodes::LatLonMuxer",
name="latlon_muxer_node_exe",
namespace="trajectory_follower",
remappings=[
("~/input/lateral/control_cmd", "lateral/control_cmd"),
("~/input/longitudinal/control_cmd", "longitudinal/control_cmd"),
("~/output/control_cmd", "control_cmd"),
],
parameters=[
latlon_muxer_param,
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
# lane departure checker
lane_departure_component = ComposableNode(
package="lane_departure_checker",
plugin="lane_departure_checker::LaneDepartureCheckerNode",
name="lane_departure_checker_node",
namespace="trajectory_follower",
remappings=[
("~/input/odometry", "/localization/kinematic_state"),
("~/input/lanelet_map_bin", "/map/vector_map"),
("~/input/route", "/planning/mission_planning/route"),
("~/input/reference_trajectory", "/planning/scenario_planning/trajectory"),
(
"~/input/predicted_trajectory",
"/control/trajectory_follower/lateral/predicted_trajectory",
),
],
parameters=[lane_departure_checker_param],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
# shift decider
shift_decider_component = ComposableNode(
package="shift_decider",
plugin="ShiftDecider",
name="shift_decider",
remappings=[
("input/control_cmd", "/control/trajectory_follower/control_cmd"),
("output/gear_cmd", "/control/shift_decider/gear_cmd"),
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
# vehicle cmd gate
vehicle_cmd_gate_component = ComposableNode(
package="vehicle_cmd_gate",
plugin="VehicleCmdGate",
name="vehicle_cmd_gate",
remappings=[
("input/emergency_state", "/system/emergency/emergency_state"),
("input/steering", "/vehicle/status/steering_status"),
("input/auto/control_cmd", "/control/trajectory_follower/control_cmd"),
("input/auto/turn_indicators_cmd", "/planning/turn_indicators_cmd"),
("input/auto/hazard_lights_cmd", "/planning/hazard_lights_cmd"),
("input/auto/gear_cmd", "/control/shift_decider/gear_cmd"),
("input/external/control_cmd", "/external/selected/control_cmd"),
("input/external/turn_indicators_cmd", "/external/selected/turn_indicators_cmd"),
("input/external/hazard_lights_cmd", "/external/selected/hazard_lights_cmd"),
("input/external/gear_cmd", "/external/selected/gear_cmd"),
("input/external_emergency_stop_heartbeat", "/external/selected/heartbeat"),
("input/gate_mode", "/control/gate_mode_cmd"),
("input/emergency/control_cmd", "/system/emergency/control_cmd"),
("input/emergency/hazard_lights_cmd", "/system/emergency/hazard_lights_cmd"),
("input/emergency/gear_cmd", "/system/emergency/gear_cmd"),
("output/vehicle_cmd_emergency", "/control/command/emergency_cmd"),
("output/control_cmd", "/control/command/control_cmd"),
("output/gear_cmd", "/control/command/gear_cmd"),
("output/turn_indicators_cmd", "/control/command/turn_indicators_cmd"),
("output/hazard_lights_cmd", "/control/command/hazard_lights_cmd"),
("output/gate_mode", "/control/current_gate_mode"),
("output/engage", "/api/autoware/get/engage"),
("output/external_emergency", "/api/autoware/get/emergency"),
("~/service/engage", "/api/autoware/set/engage"),
("~/service/external_emergency", "/api/autoware/set/emergency"),
# TODO(Takagi, Isamu): deprecated
("input/engage", "/autoware/engage"),
("~/service/external_emergency_stop", "~/external_emergency_stop"),
("~/service/clear_external_emergency_stop", "~/clear_external_emergency_stop"),
],
parameters=[
vehicle_cmd_gate_param,
{
"use_emergency_handling": LaunchConfiguration("use_emergency_handling"),
"use_external_emergency_stop": LaunchConfiguration("use_external_emergency_stop"),
"use_start_request": LaunchConfiguration("use_start_request"),
},
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
# external cmd selector
external_cmd_selector_loader = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[FindPackageShare("external_cmd_selector"), "/launch/external_cmd_selector.launch.py"]
),
launch_arguments=[
("use_intra_process", LaunchConfiguration("use_intra_process")),
("target_container", "/control/control_container"),
("initial_selector_mode", "remote"),
],
)
# external cmd converter
external_cmd_converter_loader = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[FindPackageShare("external_cmd_converter"), "/launch/external_cmd_converter.launch.py"]
),
launch_arguments=[
("use_intra_process", LaunchConfiguration("use_intra_process")),
("target_container", "/control/control_container"),
],
)
# set container to run all required components in the same process
mpc_follower_container = ComposableNodeContainer(
name="control_container",
namespace="",
package="rclcpp_components",
executable=LaunchConfiguration("container_executable"),
composable_node_descriptions=[
lon_controller_component,
latlon_muxer_component,
lane_departure_component,
shift_decider_component,
vehicle_cmd_gate_component,
],
condition=LaunchConfigurationEquals("lateral_controller_mode", "mpc_follower"),
)
pure_pursuit_container = ComposableNodeContainer(
name="control_container",
namespace="",
package="rclcpp_components",
executable=LaunchConfiguration("container_executable"),
composable_node_descriptions=[
lon_controller_component,
latlon_muxer_component,
shift_decider_component,
vehicle_cmd_gate_component,
],
condition=LaunchConfigurationEquals("lateral_controller_mode", "pure_pursuit"),
)
# lateral controller is separated since it may be another controller (e.g. pure pursuit)
mpc_follower_loader = LoadComposableNodes(
composable_node_descriptions=[mpc_follower_component],
target_container=mpc_follower_container,
condition=LaunchConfigurationEquals("lateral_controller_mode", "mpc_follower"),
)
pure_pursuit_loader = LoadComposableNodes(
composable_node_descriptions=[pure_pursuit_component],
target_container=pure_pursuit_container,
condition=LaunchConfigurationEquals("lateral_controller_mode", "pure_pursuit"),
)
group = GroupAction(
[
PushRosNamespace("control"),
mpc_follower_container,
pure_pursuit_container,
external_cmd_selector_loader,
external_cmd_converter_loader,
mpc_follower_loader,
pure_pursuit_loader,
]
)
return [group]
def generate_launch_description():
launch_arguments = []
def add_launch_arg(name: str, default_value=None, description=None):
launch_arguments.append(
DeclareLaunchArgument(name, default_value=default_value, description=description)
)
# lateral controller mode
add_launch_arg(
"lateral_controller_mode",
"mpc_follower",
"lateral controller mode: `mpc_follower` or `pure_pursuit`",
)
# parameter file path
add_launch_arg(
"lon_controller_param_path",
[
FindPackageShare("control_launch"),
"/config/trajectory_follower/longitudinal_controller.param.yaml",
],
"path to the parameter file of longitudinal controller",
)
add_launch_arg(
"latlon_muxer_param_path",
[
FindPackageShare("control_launch"),
"/config/trajectory_follower/latlon_muxer.param.yaml",
],
"path to the parameter file of latlon muxer",
)
add_launch_arg(
"vehicle_cmd_gate_param_path",
[
FindPackageShare("control_launch"),
"/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml",
],
"path to the parameter file of vehicle_cmd_gate",
)
add_launch_arg(
"lane_departure_checker_param_path",
[FindPackageShare("lane_departure_checker"), "/config/lane_departure_checker.param.yaml"],
)
# velocity controller
add_launch_arg("control_rate", "30.0", "control rate")
add_launch_arg("show_debug_info", "false", "show debug information")
add_launch_arg(
"enable_smooth_stop", "true", "enable smooth stop (in velocity controller state)"
)
add_launch_arg("enable_pub_debug", "true", "enable to publish debug information")
# vehicle cmd gate
add_launch_arg("use_emergency_handling", "false", "use emergency handling")
add_launch_arg("use_external_emergency_stop", "true", "use external emergency stop")
add_launch_arg("use_start_request", "false", "use start request service")
# external cmd selector
add_launch_arg("initial_selector_mode", "remote", "local or remote")
# component
add_launch_arg("use_intra_process", "false", "use ROS2 component container communication")
add_launch_arg("use_multithread", "false", "use multithread")
set_container_executable = SetLaunchConfiguration(
"container_executable",
"component_container",
condition=UnlessCondition(LaunchConfiguration("use_multithread")),
)
set_container_mt_executable = SetLaunchConfiguration(
"container_executable",
"component_container_mt",
condition=IfCondition(LaunchConfiguration("use_multithread")),
)
return launch.LaunchDescription(
launch_arguments
+ [
set_container_executable,
set_container_mt_executable,
]
+ [OpaqueFunction(function=launch_setup)]
)