The purpose of this package is to detect individual objects in pointcloud data. Points are grouped into clusters based on proximity and published as detected objects.
NOTE: A new version of this package is available in autoware.auto.
-
Pointcloud preprocessing
- Points closer than a distance of
remove_points_upto
meters are removed from the cloud. - Points are then downsampled if the
downsample_cloud
parameter is set to true. - The pointcloud is trimmed to remove points based on height thresholds (
clip_min_height
andclip_max_height
). - Points are further trimmed based on their y position to either side of the vehicle if
keep_lanes
is set to true. The bounds are defined bykeep_lane_left_distance
andkeep_lane_right_distance
. - A RANSAC-based algorithm is then used to determine a ground plane and remove any points belonging to the ground.
This is activated by the
remove_ground
parameter. - The pointcloud is further filtered using Difference-of-Normals to remove any points that belong to a smooth surface.
This is activated by the
use_diffnormals
parameter.
- Points closer than a distance of
-
Pointcloud Clustering
- The preprocessed pointcloud is then clustered using Euclidean Cluster Extraction, the cluster tolerance is defined by the
clustering_distance
parameter. This is the only part of the node that provides the option to use the GPU (activated by theuse_gpu
parameter). - Resulting clusters are then checked against neighboring clusters and any clusters which are less than
cluster_merge_threshold
apart are combined into a single cluster. - Rectangluar bounding boxes and polygonal bounds are then fit to the cluster pointclouds.
- The preprocessed pointcloud is then clustered using Euclidean Cluster Extraction, the cluster tolerance is defined by the
Voxel-based Downsampling
Pointcloud Surface Normal Estimation
Difference of Normals Segmentation
Euclidean Cluster Extraction
points_raw
(sensor_msgs/PointCloud2)
Input pointcloud from lidar sensor.
detection/lidar_detector/cloud_clusters
(autoware_msgs/CloudClusterArray)
Array of cloud clusters.detection/lidar_detector/objects
(autoware_msgs/DetectedObjectArray)
Array of all detected objects.cluster_centroids
(autoware_msgs/Centroids)
Centroids of the clusters.points_lanes
(sensor_msgs/PointCloud2)
Pointcloud with all preprocessing performed except Difference-of-Normals filtering.points_cluster
(sensor_msgs/PointCloud2)
Pointcloud colored according to cluster.points_ground
(sensor_msgs/PointCloud2)
Pointcloud of only ground points.
See the yaml file in the config
folder for all ROS parameters and their descriptions