forked from autowarefoundation/autoware_universe
-
Notifications
You must be signed in to change notification settings - Fork 35
/
Copy pathbag_centerline_generator.launch.xml
72 lines (62 loc) · 3.56 KB
/
bag_centerline_generator.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
<launch>
<!-- mandatory arguments for planning-->
<arg name="vehicle_model"/>
<!-- flag -->
<arg name="run_background" default="false"/>
<arg name="rviz" default="true"/>
<!-- mandatory arguments when run_background is true -->
<arg name="lanelet2_input_file_path" default=""/>
<arg name="lanelet2_output_file_path" default="/tmp/lanelet2_map.osm"/>
<arg name="start_lanelet_id" default=""/>
<arg name="end_lanelet_id" default=""/>
<!-- topic -->
<arg name="lanelet2_map_topic" default="/map/vector_map"/>
<arg name="lanelet2_map_marker_topic" default="/map/vector_map_marker"/>
<!-- param -->
<arg name="map_loader_param" default="$(find-pkg-share map_loader)/config/lanelet2_map_loader.param.yaml"/>
<arg
name="obstacle_avoidance_planner_param"
default="$(find-pkg-share autoware_launch)/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml"
/>
<arg name="mission_planner_param" default="$(find-pkg-share autoware_launch)/config/planning/mission_planning/mission_planner/mission_planner.param.yaml"/>
<!-- Global parameters (for PathFootprint in tier4_planning_rviz_plugin) -->
<!-- Do not add "group" in order to propagate global parameters -->
<include file="$(find-pkg-share global_parameter_loader)/launch/global_params.launch.py">
<arg name="vehicle_model" value="$(var vehicle_model)"/>
</include>
<!-- generate tf from "viewer" to "map" -->
<node pkg="map_tf_generator" exec="vector_map_tf_generator" name="vector_map_tf_generator">
<remap from="vector_map" to="$(var lanelet2_map_topic)"/>
<param name="map_frame" value="map"/>
<param name="viewer_frame" value="viewer"/>
</node>
<!-- visualize map -->
<node pkg="map_loader" exec="lanelet2_map_visualization" name="lanelet2_map_visualization">
<remap from="input/lanelet2_map" to="$(var lanelet2_map_topic)"/>
<remap from="output/lanelet2_map_marker" to="$(var lanelet2_map_marker_topic)"/>
</node>
<!-- optimize path -->
<node pkg="static_centerline_optimizer" exec="main2" name="bag_centerline_generator">
<remap from="lanelet2_map_topic" to="$(var lanelet2_map_topic)"/>
<remap from="input_centerline" to="~/input_centerline"/>
<remap from="output_centerline" to="~/output_centerline"/>
<remap from="debug/raw_centerline" to="~/debug/raw_centerline"/>
<remap from="debug/unsafe_footprints" to="~/debug/unsafe_footprints"/>
<param name="run_background" value="$(var run_background)"/>
<param name="lanelet2_input_file_path" value="$(var lanelet2_input_file_path)"/>
<param name="lanelet2_output_file_path" value="$(var lanelet2_output_file_path)"/>
<param name="start_lanelet_id" value="$(var start_lanelet_id)"/>
<param name="end_lanelet_id" value="$(var end_lanelet_id)"/>
<!-- common param -->
<param from="$(find-pkg-share autoware_launch)/config/planning/scenario_planning/common/common.param.yaml"/>
<param from="$(find-pkg-share autoware_launch)/config/planning/scenario_planning/common/nearest_search.param.yaml"/>
<!-- component param -->
<param from="$(var map_loader_param)"/>
<param from="$(var obstacle_avoidance_planner_param)"/>
<param from="$(var mission_planner_param)"/>
<!-- node param -->
<param from="$(find-pkg-share static_centerline_optimizer)/config/static_centerline_optimizer.param.yaml"/>
</node>
<!-- rviz -->
<node pkg="rviz2" exec="rviz2" name="rviz2" output="screen" args="-d $(find-pkg-share static_centerline_optimizer)/rviz/static_centerline_optimizer.rviz" if="$(var rviz)"/>
</launch>