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)
 Constructor. More...
 
template<typename ... Args>
void insert (Args &&... args)
 Insert an individual point. More...
 
template<typename IT >
void insert (const IT begin, const IT end)
 Multi-insert. More...
 
const Clusterscluster (const builtin_interfaces::msg::Time stamp)
 Compute the clusters from the inserted points It should in theory be ok to reinterpret_cast the points into a PointXYZI. Internally, they were constructed in place using placement new, so the dynamic type should be correct. More...
 
void cluster (Clusters &clusters)
 Compute the clusters from the inserted points, where the final clusters object lives in another scope. The final clusters object should return_clusters after being used It should in theory be ok to reinterpret_cast the points into a PointXYZI. Internally, they were constructed in place using placement new, so the dynamic type should be correct. 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...
 
void cleanup (Clusters &clusters)
 Returns the preallocated clusters to the internal pool so the cluster object can safely be resized without memory allocation due to default/copy construction. Additionally throws an error based on the result of get_error. Intended to be used with a cluster result that lives in an external scope. More...
 
const Configget_config () const
 Gets the internal configuration class, for use when it was inline generated. 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 
)

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

Member Function Documentation

◆ cleanup()

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

Returns the preallocated clusters to the internal pool so the cluster object can safely be resized without memory allocation due to default/copy construction. Additionally throws an error based on the result of get_error. Intended to be used with a cluster result that lives in an external scope.

Parameters
[in,out]clustersThe vector of clusters for which all clusters will be moved away
Exceptions
std::runtime_errorIf the maximum number of clusters may have been exceeded

◆ cluster() [1/2]

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. The final clusters object should return_clusters after being used It should in theory be ok to reinterpret_cast the points into a PointXYZI. Internally, they were constructed in place using placement new, so the dynamic type should be correct.

Parameters
[in,out]clustersThe clusters object

◆ cluster() [2/2]

const Clusters & autoware::perception::segmentation::euclidean_cluster::EuclideanCluster::cluster ( const builtin_interfaces::msg::Time  stamp)

Compute the clusters from the inserted points It should in theory be ok to reinterpret_cast the points into a PointXYZI. Internally, they were constructed in place using placement new, so the dynamic type should be correct.

Returns
A reference to the resulting clusters

◆ 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.

◆ insert() [1/2]

template<typename ... Args>
void autoware::perception::segmentation::euclidean_cluster::EuclideanCluster::insert ( Args &&...  args)
inline

Insert an individual point.

Parameters
[in]argsParameters forwarded to PointXYZII constructor (except for ID)
Exceptions
std::length_errorIf the underlying spatial hash is full

◆ insert() [2/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

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