Skip to content

Commit 44a21b0

Browse files
committedJan 29, 2024
Rework parameters of map_loader
Signed-off-by: anhnv3991 <anh.nguyen.2@tier4.jp>
1 parent f514bca commit 44a21b0

7 files changed

+121
-21
lines changed
 

‎map/map_loader/README.md

+3-14
Original file line numberDiff line numberDiff line change
@@ -111,15 +111,7 @@ Please see [the description of `GetSelectedPointCloudMap.srv`](https://github.co
111111

112112
### Parameters
113113

114-
| Name | Type | Description | Default value |
115-
| :---------------------------- | :---------- | :-------------------------------------------------------------------------------- | :------------ |
116-
| enable_whole_load | bool | A flag to enable raw pointcloud map publishing | true |
117-
| enable_downsampled_whole_load | bool | A flag to enable downsampled pointcloud map publishing | false |
118-
| enable_partial_load | bool | A flag to enable partial pointcloud map server | false |
119-
| enable_selected_load | bool | A flag to enable selected pointcloud map server | false |
120-
| leaf_size | float | Downsampling leaf size (only used when enable_downsampled_whole_load is set true) | 3.0 |
121-
| pcd_paths_or_directory | std::string | Path(s) to pointcloud map file or directory | |
122-
| pcd_metadata_path | std::string | Path to pointcloud metadata file | |
114+
{{ json_to_markdown("map/map_loader/schema/pointcloud_map_loader.schema.json") }}
123115

124116
### Interfaces
125117

@@ -144,7 +136,7 @@ Please see [tier4_autoware_msgs/msg/MapProjectorInfo.msg](https://github.com/tie
144136

145137
### How to run
146138

147-
`ros2 run map_loader lanelet2_map_loader --ros-args -p lanelet2_map_path:=path/to/map.osm`
139+
`ros2 run map_loader lanelet2_map_loader`
148140

149141
### Subscribed Topics
150142

@@ -156,10 +148,7 @@ Please see [tier4_autoware_msgs/msg/MapProjectorInfo.msg](https://github.com/tie
156148

157149
### Parameters
158150

159-
| Name | Type | Description | Default value |
160-
| :--------------------- | :---------- | :----------------------------------------------- | :------------ |
161-
| center_line_resolution | double | Define the resolution of the lanelet center line | 5.0 |
162-
| lanelet2_map_path | std::string | The lanelet2 map path | None |
151+
{{ json_to_markdown("map/map_loader/schema/lanelet2_map_loader.schema.json") }}
163152

164153
---
165154

Original file line numberDiff line numberDiff line change
@@ -1,3 +1,4 @@
11
/**:
22
ros__parameters:
33
center_line_resolution: 5.0 # [m]
4+
lanelet2_map_path: "" # The lanelet2 map path

‎map/map_loader/config/pointcloud_map_loader.param.yaml

+2
Original file line numberDiff line numberDiff line change
@@ -7,3 +7,5 @@
77

88
# only used when downsample_whole_load enabled
99
leaf_size: 3.0 # downsample leaf size [m]
10+
pcd_paths_or_directory: [] # Path to the pointcloud map file or directory
11+
pcd_metadata_path: "" # Path to pointcloud metadata file

‎map/map_loader/launch/lanelet2_map_loader.launch.xml

+1-3
Original file line numberDiff line numberDiff line change
@@ -1,16 +1,14 @@
11
<launch>
22
<arg name="lanelet2_map_loader_param_path" default="$(find-pkg-share map_loader)/config/lanelet2_map_loader.param.yaml"/>
3-
<arg name="lanelet2_map_path"/>
43
<arg name="lanelet2_map_topic" default="vector_map"/>
54
<arg name="lanelet2_map_marker_topic" default="vector_map_marker"/>
65

76
<node pkg="map_loader" exec="map_hash_generator" name="map_hash_generator">
8-
<param name="lanelet2_map_path" value="$(var lanelet2_map_path)"/>
7+
<param from="$(var lanelet2_map_loader_param_path)"/>
98
</node>
109

1110
<node pkg="map_loader" exec="lanelet2_map_loader" name="lanelet2_map_loader">
1211
<remap from="output/lanelet2_map" to="$(var lanelet2_map_topic)"/>
13-
<param name="lanelet2_map_path" value="$(var lanelet2_map_path)"/>
1412
<param from="$(var lanelet2_map_loader_param_path)"/>
1513
</node>
1614

Original file line numberDiff line numberDiff line change
@@ -1,14 +1,10 @@
11
<launch>
2-
<arg name="pointcloud_map_path"/>
3-
<arg name="pointcloud_map_metadata_path"/>
42
<arg name="pointcloud_map_loader_param_path" default="$(find-pkg-share map_loader)/config/pointcloud_map_loader.param.yaml"/>
53

64
<node pkg="map_loader" exec="pointcloud_map_loader" name="pointcloud_map_loader" output="screen">
75
<remap from="output/pointcloud_map" to="/map/pointcloud_map"/>
86
<remap from="service/get_partial_pcd_map" to="/map/get_partial_pointcloud_map"/>
97
<remap from="service/get_selected_pcd_map" to="/map/get_selected_pointcloud_map"/>
10-
<param name="pcd_paths_or_directory" value="[$(var pointcloud_map_path)]"/>
11-
<param name="pcd_metadata_path" value="$(var pcd_metadata_path)"/>
128
<param from="$(var pointcloud_map_loader_param_path)"/>
139
</node>
1410
</launch>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,42 @@
1+
{
2+
"$schema": "http://json-schema.org/draft-07/schema#",
3+
"title": "Parameters for lanelet2 map loader Node",
4+
"type": "object",
5+
"definitions": {
6+
"lanelet2_map_loader": {
7+
"type": "object",
8+
"properties": {
9+
"center_line_resolution": {
10+
"type": "number",
11+
"description": "Resolution of the Lanelet center line [m]",
12+
"default": "5.0"
13+
},
14+
"lanelet2_map_path": {
15+
"type": "string",
16+
"description": "The lanelet2 map path pointing to the .osm file",
17+
"default": ""
18+
}
19+
},
20+
"required": [
21+
"center_line_resolution",
22+
"lanelet2_map_path"
23+
],
24+
"additionalProperties": false
25+
}
26+
},
27+
"properties": {
28+
"/**": {
29+
"type": "object",
30+
"properties": {
31+
"ros__parameters": {
32+
"$ref": "#/definitions/lanelet2_map_loader"
33+
}
34+
},
35+
"required": ["ros__parameters"],
36+
"additionalProperties": false
37+
}
38+
},
39+
"required": ["/**"],
40+
"additionalProperties": false
41+
}
42+
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,72 @@
1+
{
2+
"$schema": "http://json-schema.org/draft-07/schema#",
3+
"title": "Parameters for point cloud map loader Node",
4+
"type": "object",
5+
"definitions": {
6+
"pointcloud_map_loader": {
7+
"type": "object",
8+
"properties": {
9+
"enable_whole_load": {
10+
"type": "boolean",
11+
"description": "Enable raw pointcloud map publishing",
12+
"default": true
13+
},
14+
"enable_downsampled_whole_load": {
15+
"type": "boolean",
16+
"description": "Enable downsampled pointcloud map publishing",
17+
"default": false
18+
},
19+
"enable_partial_load": {
20+
"type": "boolean",
21+
"description": "Enable partial pointcloud map server",
22+
"default": true
23+
},
24+
"enable_selected_load": {
25+
"type": "boolean",
26+
"description": "Enable selected pointcloud map server",
27+
"default": false
28+
},
29+
"leaf_size": {
30+
"type": "number",
31+
"description": "Downsampling leaf size (only used when enable_downsampled_whole_load is set true)",
32+
"default": 3.0
33+
},
34+
"pcd_paths_or_directory": {
35+
"type": "array",
36+
"description": "Path(s) to pointcloud map file or directory",
37+
"default": []
38+
},
39+
"pcd_metadata_path": {
40+
"type": "string",
41+
"description": "Path to pointcloud metadata file",
42+
"default": ""
43+
}
44+
},
45+
"required": [
46+
"enable_whole_load",
47+
"enable_downsampled_whole_load",
48+
"enable_partial_load",
49+
"enable_selected_load",
50+
"leaf_size",
51+
"pcd_paths_or_directory",
52+
"pcd_metadata_path"
53+
],
54+
"additionalProperties": false
55+
}
56+
},
57+
"properties": {
58+
"/**": {
59+
"type": "object",
60+
"properties": {
61+
"ros__parameters": {
62+
"$ref": "#/definitions/pointcloud_map_loader"
63+
}
64+
},
65+
"required": ["ros__parameters"],
66+
"additionalProperties": false
67+
}
68+
},
69+
"required": ["/**"],
70+
"additionalProperties": false
71+
}
72+

0 commit comments

Comments
 (0)