/
behavior_planning.launch.xml
299 lines (289 loc) · 17.5 KB
/
behavior_planning.launch.xml
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
<launch>
<arg name="input_route_topic_name" default="/planning/mission_planning/route"/>
<arg name="input_traffic_light_topic_name" default="/perception/traffic_light_recognition/traffic_signals"/>
<arg name="input_virtual_traffic_light_topic_name" default="/awapi/tmp/virtual_traffic_light_states"/>
<arg name="input_vector_map_topic_name" default="/map/vector_map"/>
<arg name="input_pointcloud_map_topic_name" default="/map/pointcloud_map"/>
<arg name="enable_all_modules_auto_mode"/>
<arg name="is_simulation"/>
<arg name="launch_avoidance_module" default="true"/>
<arg name="launch_avoidance_by_lane_change_module" default="true"/>
<arg name="launch_dynamic_avoidance_module" default="true"/>
<arg name="launch_lane_change_right_module" default="true"/>
<arg name="launch_lane_change_left_module" default="true"/>
<arg name="launch_external_request_lane_change_right_module" default="true"/>
<arg name="launch_external_request_lane_change_left_module" default="true"/>
<arg name="launch_goal_planner_module" default="true"/>
<arg name="launch_start_planner_module" default="true"/>
<arg name="launch_sampling_planner_module" default="true"/>
<arg name="launch_side_shift_module" default="true"/>
<arg name="launch_crosswalk_module" default="true"/>
<arg name="launch_walkway_module" default="true"/>
<arg name="launch_traffic_light_module" default="true"/>
<arg name="launch_intersection_module" default="true"/>
<arg name="launch_merge_from_private_module" default="true"/>
<arg name="launch_blind_spot_module" default="true"/>
<arg name="launch_detection_area_module" default="true"/>
<arg name="launch_virtual_traffic_light_module" default="true"/>
<arg name="launch_no_stopping_area_module" default="true"/>
<arg name="launch_stop_line_module" default="true"/>
<arg name="launch_occlusion_spot_module" default="true"/>
<arg name="launch_run_out_module" default="true"/>
<arg name="launch_speed_bump_module" default="true"/>
<arg name="launch_out_of_lane_module" default="true"/>
<arg name="launch_no_drivable_lane_module" default="true"/>
<arg name="launch_dynamic_obstacle_stop_module" default="true"/>
<arg name="launch_module_list_end" default="""]"/>
<!-- assemble launch config for behavior path planner -->
<arg name="behavior_path_planner_launch_modules" default="["/>
<let
name="behavior_path_planner_launch_modules"
value="$(eval "'$(var behavior_path_planner_launch_modules)' + 'behavior_path_planner::AvoidanceModuleManager, '")"
if="$(var launch_avoidance_module)"
/>
<let
name="behavior_path_planner_launch_modules"
value="$(eval "'$(var behavior_path_planner_launch_modules)' + 'behavior_path_planner::DynamicAvoidanceModuleManager, '")"
if="$(var launch_dynamic_avoidance_module)"
/>
<let
name="behavior_path_planner_launch_modules"
value="$(eval "'$(var behavior_path_planner_launch_modules)' + 'behavior_path_planner::SideShiftModuleManager, '")"
if="$(var launch_side_shift_module)"
/>
<let
name="behavior_path_planner_launch_modules"
value="$(eval "'$(var behavior_path_planner_launch_modules)' + 'behavior_path_planner::StartPlannerModuleManager, '")"
if="$(var launch_start_planner_module)"
/>
<let
name="behavior_path_planner_launch_modules"
value="$(eval "'$(var behavior_path_planner_launch_modules)' + 'behavior_path_planner::SamplingPlannerModuleManager, '")"
if="$(var launch_sampling_planner_module)"
/>
<let
name="behavior_path_planner_launch_modules"
value="$(eval "'$(var behavior_path_planner_launch_modules)' + 'behavior_path_planner::GoalPlannerModuleManager, '")"
if="$(var launch_goal_planner_module)"
/>
<let
name="behavior_path_planner_launch_modules"
value="$(eval "'$(var behavior_path_planner_launch_modules)' + 'behavior_path_planner::LaneChangeRightModuleManager, '")"
if="$(var launch_lane_change_right_module)"
/>
<let
name="behavior_path_planner_launch_modules"
value="$(eval "'$(var behavior_path_planner_launch_modules)' + 'behavior_path_planner::LaneChangeLeftModuleManager, '")"
if="$(var launch_lane_change_left_module)"
/>
<let
name="behavior_path_planner_launch_modules"
value="$(eval "'$(var behavior_path_planner_launch_modules)' + 'behavior_path_planner::ExternalRequestLaneChangeRightModuleManager, '")"
if="$(var launch_external_request_lane_change_right_module)"
/>
<let
name="behavior_path_planner_launch_modules"
value="$(eval "'$(var behavior_path_planner_launch_modules)' + 'behavior_path_planner::ExternalRequestLaneChangeLeftModuleManager, '")"
if="$(var launch_external_request_lane_change_left_module)"
/>
<let
name="behavior_path_planner_launch_modules"
value="$(eval "'$(var behavior_path_planner_launch_modules)' + 'behavior_path_planner::AvoidanceByLaneChangeModuleManager, '")"
if="$(var launch_avoidance_by_lane_change_module)"
/>
<let name="behavior_path_planner_launch_modules" value="$(eval "'$(var behavior_path_planner_launch_modules)' + '$(var launch_module_list_end)'")"/>
<!-- assemble launch config for behavior velocity planner -->
<arg name="behavior_velocity_planner_launch_modules" default="["/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval "'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::CrosswalkModulePlugin, '")"
if="$(var launch_crosswalk_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval "'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::WalkwayModulePlugin, '")"
if="$(var launch_walkway_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval "'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::TrafficLightModulePlugin, '")"
if="$(var launch_traffic_light_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval "'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::IntersectionModulePlugin, '")"
if="$(var launch_intersection_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval "'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::MergeFromPrivateModulePlugin, '")"
if="$(var launch_merge_from_private_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval "'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::BlindSpotModulePlugin, '")"
if="$(var launch_blind_spot_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval "'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::DetectionAreaModulePlugin, '")"
if="$(var launch_detection_area_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval "'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::VirtualTrafficLightModulePlugin, '")"
if="$(var launch_virtual_traffic_light_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval "'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::NoStoppingAreaModulePlugin, '")"
if="$(var launch_no_stopping_area_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval "'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::StopLineModulePlugin, '")"
if="$(var launch_stop_line_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval "'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::OcclusionSpotModulePlugin, '")"
if="$(var launch_occlusion_spot_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval "'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::RunOutModulePlugin, '")"
if="$(var launch_run_out_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval "'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::SpeedBumpModulePlugin, '")"
if="$(var launch_speed_bump_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval "'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::OutOfLaneModulePlugin, '")"
if="$(var launch_out_of_lane_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval "'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::NoDrivableLaneModulePlugin, '")"
if="$(var launch_no_drivable_lane_module)"
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval "'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::DynamicObstacleStopModulePlugin, '")"
if="$(var launch_dynamic_obstacle_stop_module)"
/>
<let name="behavior_velocity_planner_launch_modules" value="$(eval "'$(var behavior_velocity_planner_launch_modules)' + '$(var launch_module_list_end)'")"/>
<node_container pkg="rclcpp_components" exec="$(var container_type)" name="behavior_planning_container" namespace="" args="" output="both">
<composable_node pkg="behavior_path_planner" plugin="behavior_path_planner::BehaviorPathPlannerNode" name="behavior_path_planner" namespace="">
<!-- topic remap -->
<remap from="~/input/route" to="$(var input_route_topic_name)"/>
<remap from="~/input/vector_map" to="$(var input_vector_map_topic_name)"/>
<remap from="~/input/perception" to="/perception/object_recognition/objects"/>
<remap from="~/input/occupancy_grid_map" to="/perception/occupancy_grid_map/map"/>
<remap from="~/input/costmap" to="/planning/scenario_planning/parking/costmap_generator/occupancy_grid"/>
<remap from="~/input/traffic_signals" to="$(var input_traffic_light_topic_name)"/>
<remap from="~/input/odometry" to="/localization/kinematic_state"/>
<remap from="~/input/accel" to="/localization/acceleration"/>
<remap from="~/input/scenario" to="/planning/scenario_planning/scenario"/>
<remap from="~/output/path" to="path_with_lane_id"/>
<remap from="~/output/turn_indicators_cmd" to="/planning/turn_indicators_cmd"/>
<remap from="~/output/hazard_lights_cmd" to="/planning/hazard_lights_cmd"/>
<remap from="~/output/modified_goal" to="/planning/scenario_planning/modified_goal"/>
<remap from="~/output/stop_reasons" to="/planning/scenario_planning/status/stop_reasons"/>
<!-- params -->
<param from="$(var common_param_path)"/>
<param from="$(var vehicle_param_file)"/>
<param from="$(var nearest_search_param_path)"/>
<param name="launch_modules" value="$(var behavior_path_planner_launch_modules)"/>
<param name="enable_all_modules_auto_mode" value="$(var enable_all_modules_auto_mode)"/>
<param name="is_simulation" value="$(var is_simulation)"/>
<param from="$(var behavior_path_planner_side_shift_module_param_path)"/>
<param from="$(var behavior_path_planner_avoidance_module_param_path)"/>
<param from="$(var behavior_path_planner_avoidance_by_lc_module_param_path)"/>
<param from="$(var behavior_path_planner_dynamic_avoidance_module_param_path)"/>
<param from="$(var behavior_path_planner_lane_change_module_param_path)"/>
<param from="$(var behavior_path_planner_goal_planner_module_param_path)"/>
<param from="$(var behavior_path_planner_start_planner_module_param_path)"/>
<param from="$(var behavior_path_planner_sampling_planner_module_param_path)"/>
<param from="$(var behavior_path_planner_drivable_area_expansion_param_path)"/>
<param from="$(var behavior_path_planner_scene_module_manager_param_path)"/>
<param from="$(var behavior_path_planner_common_param_path)"/>
<!-- composable node config -->
<extra_arg name="use_intra_process_comms" value="false"/>
</composable_node>
<composable_node pkg="behavior_velocity_planner" plugin="behavior_velocity_planner::BehaviorVelocityPlannerNode" name="behavior_velocity_planner" namespace="">
<!-- topic remap -->
<remap from="~/input/path_with_lane_id" to="path_with_lane_id"/>
<remap from="~/input/vector_map" to="$(var input_vector_map_topic_name)"/>
<remap from="~/input/vehicle_odometry" to="/localization/kinematic_state"/>
<remap from="~/input/accel" to="/localization/acceleration"/>
<remap from="~/input/dynamic_objects" to="/perception/object_recognition/objects"/>
<remap from="~/input/no_ground_pointcloud" to="/perception/obstacle_segmentation/pointcloud"/>
<remap from="~/input/compare_map_filtered_pointcloud" to="compare_map_filtered/pointcloud"/>
<remap from="~/input/vector_map_inside_area_filtered_pointcloud" to="vector_map_inside_area_filtered/pointcloud"/>
<remap from="~/input/external_velocity_limit_mps" to="/planning/scenario_planning/max_velocity_default"/>
<remap from="~/input/traffic_signals" to="$(var input_traffic_light_topic_name)"/>
<remap from="~/input/virtual_traffic_light_states" to="$(var input_virtual_traffic_light_topic_name)"/>
<remap from="~/input/occupancy_grid" to="/perception/occupancy_grid_map/map"/>
<remap from="~/output/path" to="path"/>
<remap from="~/output/stop_reasons" to="/planning/scenario_planning/status/stop_reasons"/>
<remap from="~/output/infrastructure_commands" to="/planning/scenario_planning/status/infrastructure_commands"/>
<remap from="~/output/traffic_signal" to="debug/traffic_signal"/>
<!-- params -->
<param from="$(var common_param_path)"/>
<param from="$(var vehicle_param_file)"/>
<param from="$(var nearest_search_param_path)"/>
<param from="$(var motion_velocity_smoother_param_path)"/>
<param from="$(var behavior_velocity_smoother_type_param_path)"/>
<param from="$(var behavior_velocity_planner_common_param_path)"/>
<param name="launch_modules" value="$(var behavior_velocity_planner_launch_modules)"/>
<param name="enable_all_modules_auto_mode" value="$(var enable_all_modules_auto_mode)"/>
<param name="is_simulation" value="$(var is_simulation)"/>
<!-- <param from="$(var template_param_path)"/> -->
<param from="$(var behavior_velocity_planner_blind_spot_module_param_path)"/>
<param from="$(var behavior_velocity_planner_crosswalk_module_param_path)"/>
<param from="$(var behavior_velocity_planner_walkway_module_param_path)"/>
<param from="$(var behavior_velocity_planner_detection_area_module_param_path)"/>
<param from="$(var behavior_velocity_planner_intersection_module_param_path)"/>
<param from="$(var behavior_velocity_planner_stop_line_module_param_path)"/>
<param from="$(var behavior_velocity_planner_traffic_light_module_param_path)"/>
<param from="$(var behavior_velocity_planner_virtual_traffic_light_module_param_path)"/>
<param from="$(var behavior_velocity_planner_occlusion_spot_module_param_path)"/>
<param from="$(var behavior_velocity_planner_no_stopping_area_module_param_path)"/>
<param from="$(var behavior_velocity_planner_run_out_module_param_path)"/>
<param from="$(var behavior_velocity_planner_speed_bump_module_param_path)"/>
<param from="$(var behavior_velocity_planner_out_of_lane_module_param_path)"/>
<param from="$(var behavior_velocity_planner_no_drivable_lane_module_param_path)"/>
<param from="$(var behavior_velocity_planner_dynamic_obstacle_stop_module_param_path)"/>
<!-- composable node config -->
<extra_arg name="use_intra_process_comms" value="false"/>
</composable_node>
<composable_node pkg="glog_component" plugin="GlogComponent" name="glog_component" namespace=""/>
</node_container>
<group if="$(var launch_compare_map_pipeline)">
<!-- use pointcloud container -->
<load_composable_node target="$(var pointcloud_container_name)">
<composable_node pkg="compare_map_segmentation" plugin="compare_map_segmentation::VoxelDistanceBasedCompareMapFilterComponent" name="voxel_distance_based_compare_map_filter_node" namespace="">
<!-- topic remap -->
<remap from="map" to="$(var input_pointcloud_map_topic_name)"/>
<remap from="kinematic_state" to="/localization/kinematic_state"/>
<remap from="map_loader_service" to="/map/get_differential_pointcloud_map"/>
<remap from="input" to="/perception/obstacle_segmentation/pointcloud"/>
<remap from="output" to="compare_map_filtered/pointcloud"/>
<!-- params -->
<param from="$(var compare_map_filter_param_path)"/>
<extra_arg name="use_intra_process_comms" value="false"/>
</composable_node>
<composable_node pkg="pointcloud_preprocessor" plugin="pointcloud_preprocessor::VectorMapInsideAreaFilterComponent" name="vector_map_inside_area_filter_node" namespace="">
<!-- topic remap -->
<remap from="input/vector_map" to="$(var input_vector_map_topic_name)"/>
<remap from="input" to="compare_map_filtered/pointcloud"/>
<remap from="output" to="vector_map_inside_area_filtered/pointcloud"/>
<param name="polygon_type" value="no_obstacle_segmentation_area_for_run_out"/>
<extra_arg name="use_intra_process_comms" value="false"/>
</composable_node>
</load_composable_node>
</group>
</launch>