Autoware.Auto
autoware::perception::segmentation::euclidean_cluster::EuclideanCluster Class Reference

implementation of euclidean clustering for point cloud segmentation This clas implicitly projects points onto a 2D (x-y) plane, and segments according to euclidean distance. This can be thought of as a graph-based approach where points are vertices and edges are defined by euclidean distance The input to this should be nonground points pased through a voxel grid. More...

#include <euclidean_cluster.hpp>

Public Types

enum  Error : uint8_t { Error::NONE = 0U, Error::TOO_MANY_CLUSTERS }
 

Public Member Functions

 EuclideanCluster (const Config &cfg, const HashConfig &hash_cfg, const FilterConfig &filter_cfg)
 Constructor. More...
 
void insert (const PointXYZIR &pt)
 Insert an individual point. More...
 
template<typename IT >
void insert (const IT begin, const IT end)
 Multi-insert. More...
 
void cluster (Clusters &clusters)
 Compute the clusters from the inserted points, where the final clusters object lives in another scope. More...
 
Error get_error () const
 Gets last error, intended to be used with clustering with internal cluster result This is a separate function rather than using an exception because the main error mode is exceeding preallocated cluster capacity. However, throwing an exception would throw away perfectly valid information that is still usable in an error state. More...
 
const Configget_config () const
 Gets the internal configuration class, for use when it was inline generated. More...
 
const FilterConfigget_filter_config () const
 Gets internal configuration class for filters. More...
 
void throw_stored_error () const
 Throw the stored error during clustering process. More...
 

Detailed Description

implementation of euclidean clustering for point cloud segmentation This clas implicitly projects points onto a 2D (x-y) plane, and segments according to euclidean distance. This can be thought of as a graph-based approach where points are vertices and edges are defined by euclidean distance The input to this should be nonground points pased through a voxel grid.

Member Enumeration Documentation

◆ Error

Enumerator
NONE 
TOO_MANY_CLUSTERS 

Constructor & Destructor Documentation

◆ EuclideanCluster()

autoware::perception::segmentation::euclidean_cluster::EuclideanCluster::EuclideanCluster ( const Config cfg,
const HashConfig hash_cfg,
const FilterConfig filter_cfg 
)

Constructor.

Parameters
[in]cfgThe configuration of the clustering algorithm, contains threshold function
[in]hash_cfgThe configuration of the underlying spatial hash, controls the maximum number of points in a scene
[in]filter_cfgThe configuration of the min/max size limit of the bounding boxes

Member Function Documentation

◆ cluster()

void autoware::perception::segmentation::euclidean_cluster::EuclideanCluster::cluster ( Clusters clusters)

Compute the clusters from the inserted points, where the final clusters object lives in another scope.

Parameters
[in,out]clustersThe clusters object

◆ get_config()

const Config & autoware::perception::segmentation::euclidean_cluster::EuclideanCluster::get_config ( ) const

Gets the internal configuration class, for use when it was inline generated.

Returns
Internal configuration class

◆ get_error()

EuclideanCluster::Error autoware::perception::segmentation::euclidean_cluster::EuclideanCluster::get_error ( ) const

Gets last error, intended to be used with clustering with internal cluster result This is a separate function rather than using an exception because the main error mode is exceeding preallocated cluster capacity. However, throwing an exception would throw away perfectly valid information that is still usable in an error state.

◆ get_filter_config()

const FilterConfig & autoware::perception::segmentation::euclidean_cluster::EuclideanCluster::get_filter_config ( ) const

Gets internal configuration class for filters.

Returns
Internal FilterConfiguration class

◆ insert() [1/2]

template<typename IT >
void autoware::perception::segmentation::euclidean_cluster::EuclideanCluster::insert ( const IT  begin,
const IT  end 
)
inline

Multi-insert.

Parameters
[in]beginIterator pointing to to the first point to insert
[in]endIterator pointing to one past the last point to insert
Exceptions
std::length_errorIf the underlying spatial hash is full
Template Parameters
ITThe type of the iterator

◆ insert() [2/2]

void autoware::perception::segmentation::euclidean_cluster::EuclideanCluster::insert ( const PointXYZIR pt)

Insert an individual point.

Parameters
[in]ptThe point to insert
Exceptions
std::length_errorIf the underlying spatial hash is full

◆ throw_stored_error()

void autoware::perception::segmentation::euclidean_cluster::EuclideanCluster::throw_stored_error ( ) const

Throw the stored error during clustering process.

Exceptions
std::runtime_errorIf the maximum number of clusters may have been exceeded

The documentation for this class was generated from the following files: