autoware_elevation_map_loader#
Purpose#
This package provides elevation map for autoware_compare_map_segmentation.
Inner-workings / Algorithms#
Generate elevation_map from subscribed pointcloud_map and vector_map and publish it. Save the generated elevation_map locally and load it from next time.
The elevation value of each cell is the average value of z of the points of the lowest cluster.
Cells with No elevation value can be inpainted using the values of neighboring cells.
Inputs / Outputs#
Input#
Name | Type | Description |
---|---|---|
input/pointcloud_map |
sensor_msgs::msg::PointCloud2 |
The point cloud map |
input/vector_map |
autoware_map_msgs::msg::LaneletMapBin |
(Optional) The binary data of lanelet2 map |
input/pointcloud_map_metadata |
autoware_map_msgs::msg::PointCloudMapMetaData |
(Optional) The metadata of point cloud map |
Output#
Name | Type | Description |
---|---|---|
output/elevation_map |
grid_map_msgs::msg::GridMap |
The elevation map |
output/elevation_map_cloud |
sensor_msgs::msg::PointCloud2 |
(Optional) The point cloud generated from the value of elevation map |
Service#
Name | Type | Description |
---|---|---|
service/get_selected_pcd_map |
autoware_map_msgs::srv::GetSelectedPointCloudMap |
(Optional) service to request point cloud map. If pointcloud_map_loader uses selected pointcloud map loading via ROS 2 service, use this. |
Parameters#
Node Parameters#
Name | Type | Description | Default | Range |
---|---|---|---|---|
map_layer_name | string | elevation_map layer name | elevation | N/A |
param_file_path | string | GridMap parameters config | path_default | N/A |
map_frame | string | map_frame when loading elevation_map file | map | N/A |
use_sequential_load | boolean | Whether to get point cloud map by service | True | N/A |
sequential_map_load_num | integer | The number of point cloud maps to load at once (only used when use_sequential_load is set true). This should not be larger than number of all point cloud map cells | 1 | ≥1 |
use_inpaint | boolean | Whether to inpaint empty cells | True | N/A |
inpaint_radius | float | Radius of a circular neighborhood of each point inpainted that is considered by the algorithm [m] | 0.3 | ≥0 |
use_elevation_map_cloud_publisher | boolean | Whether to publish output/elevation_map_cloud |
False | N/A |
elevation_map_directory | string | elevation_map file (bag2) | path_default | N/A |
use_lane_filter | boolean | Whether to filter elevation_map with vector_map | False | N/A |
lane_margin | float | Margin distance from the lane polygon of the area to be included in the inpainting mask [m]. Used only when use_lane_filter=True | 0.0 | ≥0 |
Grid Map Parameters#
See: https://github.com/ANYbotics/grid_map/tree/ros2/grid_map_pcl
Name | Type | Description | Default | Range |
---|---|---|---|---|
num_processing_threads | float | Number of threads for processing grid map cells. Filtering of the raw input point cloud is not parallelized | 12 | ≥1 |
min_num_points_per_cell | integer | Minimum number of points in the point cloud that have to fall within any of the grid map cells. Otherwise the cell elevation will be set to NaN | 3 | ≥1 |
resolution | float | Resolution of the grid map. Width and length are computed automatically | 0.3 | ≥0.01 |
height_type | integer | Resolution of the grid map. Width and length are computed automatically. | 1 | N/A |
height_thresh | float | Height range from the smallest cluster (Only for height_type 1) | 1 | N/A |
Point Cloud Preprocessing Parameters#
Rigid body transform parameters#
Rigid body transform that is applied to the point cloud before computing elevation.
Name | Type | Description | Default | Range |
---|---|---|---|---|
x | float | Translation (x) that is applied to the input point cloud before computing elevation | 0 | N/A |
y | float | Translation (y) that is applied to the input point cloud before computing elevation | 0 | N/A |
z | float | Translation (z) that is applied to the input point cloud before computing elevation | 0 | N/A |
Name | Type | Description | Default | Range |
-------- | -------- | ------------------------------------------------------------------------------------------------------------------------- | ----------- | -------------------- |
r | float | Rotation (intrinsic rotation, convention X-Y'-Z'') that is applied to the input point cloud before computing elevation. | 0 | ≥-360.0 ≤360.0 |
p | float | Rotation (intrinsic rotation, convention X-Y'-Z'') that is applied to the input point cloud before computing elevation. | 0 | ≥-360.0 ≤360.0 |
y | float | Rotation (intrinsic rotation, convention X-Y'-Z'') that is applied to the input point cloud before computing elevation. | 0 | ≥-360.0 ≤360.0 |
Cluster Extraction Parameters#
Cluster extraction is based on pcl algorithms. See https://pointclouds.org/documentation/tutorials/cluster_extraction.html for more details.
Name | Type | Description | Default | Range |
---|---|---|---|---|
cluster_tolerance | float | Distance between points below which they will still be considered part of one cluster | 0.2 | ≥0.01 |
min_num_points | integer | Min number of points that a cluster needs to have (otherwise it will be discarded) | 3 | ≥1 |
max_num_points | integer | Max number of points that a cluster can have (otherwise it will be discarded) | 1e+06 | N/A |
Outlier Removal Parameters#
See https://pointclouds.org/documentation/tutorials/statistical_outlier.html for more explanation on outlier removal.
Name | Type | Description | Default | Range |
---|---|---|---|---|
is_remove_outliers | boolean | Whether to perform statistical outlier removal | 0 | N/A |
mean_K | float | Number of neighbors to analyze for estimating statistics of a point | 10 | ≥1 |
stddev_threshold | float | Number of standard deviations under which points are considered to be inliers | 1 | N/A |
Subsampling Parameters#
See https://pointclouds.org/documentation/tutorials/voxel_grid.html for more explanation on point cloud downsampling.
Name | Type | Description | Default | Range |
---|---|---|---|---|
is_downsample_cloud | boolean | Whether to perform downsampling or not | False | N/A |
Name | Type | Description | Default | Range |
-------- | -------- | ------------------------- | ----------- | --------- |
x | float | Voxel size(x) in meters | 0.02 | ≥0.001 |
y | float | Voxel size(y) in meters | 0.02 | ≥0.001 |
z | float | Voxel size(z) in meters | 0.02 | ≥0.001 |