forked from autowarefoundation/autoware_universe
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathmap.launch.xml
68 lines (58 loc) · 3.41 KB
/
map.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
<launch>
<!-- map files -->
<arg name="pointcloud_map_path"/>
<arg name="pointcloud_map_metadata_path"/>
<arg name="lanelet2_map_path"/>
<arg name="map_projector_info_path"/>
<!-- Parameter files -->
<arg name="pointcloud_map_loader_param_path"/>
<arg name="lanelet2_map_loader_param_path"/>
<arg name="map_tf_generator_param_path"/>
<arg name="map_projection_loader_param_path"/>
<!-- whether use intra-process -->
<arg name="use_intra_process" default="false"/>
<!-- select container type -->
<arg name="use_multithread" default="false"/>
<let name="container_type" value="component_container" unless="$(var use_multithread)"/>
<let name="container_type" value="component_container_mt" if="$(var use_multithread)"/>
<group>
<push-ros-namespace namespace="map"/>
<node_container pkg="rclcpp_components" exec="$(var container_type)" name="map_container" namespace="" output="screen">
<composable_node pkg="map_loader" plugin="PointCloudMapLoaderNode" name="pointcloud_map_loader">
<param from="$(var pointcloud_map_loader_param_path)"/>
<param name="pcd_paths_or_directory" value="[$(var pointcloud_map_path)]"/>
<param name="pcd_metadata_path" value="$(var pointcloud_map_metadata_path)"/>
<remap from="output/pointcloud_map" to="pointcloud_map"/>
<remap from="output/pointcloud_map_metadata" to="pointcloud_map_metadata"/>
<remap from="service/get_partial_pcd_map" to="/map/get_partial_pointcloud_map"/>
<remap from="service/get_differential_pcd_map" to="/map/get_differential_pointcloud_map"/>
<remap from="service/get_selected_pcd_map" to="/map/get_selected_pointcloud_map"/>
<extra_arg name="use_intra_process_comms" value="$(var use_intra_process)"/>
</composable_node>
<composable_node pkg="map_loader" plugin="Lanelet2MapLoaderNode" name="lanelet2_map_loader">
<param from="$(var lanelet2_map_loader_param_path)"/>
<param name="lanelet2_map_path" value="$(var lanelet2_map_path)"/>
<remap from="output/lanelet2_map" to="vector_map"/>
<extra_arg name="use_intra_process_comms" value="$(var use_intra_process)"/>
</composable_node>
<composable_node pkg="map_loader" plugin="Lanelet2MapVisualizationNode" name="lanelet2_map_visualization">
<remap from="input/lanelet2_map" to="vector_map"/>
<remap from="output/lanelet2_map_marker" to="vector_map_marker"/>
<extra_arg name="use_intra_process_comms" value="$(var use_intra_process)"/>
</composable_node>
<composable_node pkg="map_tf_generator" plugin="VectorMapTFGeneratorNode" name="vector_map_tf_generator">
<param from="$(var map_tf_generator_param_path)"/>
<extra_arg name="use_intra_process_comms" value="$(var use_intra_process)"/>
</composable_node>
</node_container>
<node pkg="map_loader" exec="map_hash_generator" name="map_hash_generator">
<param name="lanelet2_map_path" value="$(var lanelet2_map_path)"/>
<param name="pointcloud_map_path" value="$(var pointcloud_map_path)"/>
</node>
<include file="$(find-pkg-share map_projection_loader)/launch/map_projection_loader.launch.xml">
<arg name="param_path" value="$(var map_projection_loader_param_path)"/>
<arg name="map_projector_info_path" value="$(var map_projector_info_path)"/>
<arg name="lanelet2_map_path" value="$(var lanelet2_map_path)"/>
</include>
</group>
</launch>