Functions
clustering.cpp File Reference

Clustering related functions. More...

#include "clustering.h"
#include "lidar_segmentation.h"
Include dependency graph for clustering.cpp:

Go to the source code of this file.

Functions

int abdClustering (vector< PointPtr > &points, double lambda, vector< ClusterPtr > &clusters_ABD)
 Performs Segmentation operation with the Adaptative Breakpoint Detector. More...
 
PointPtr calculateClusterCentroid (vector< PointPtr > support_points)
 Calculates the cluster's centroid. More...
 
geometry_msgs::Point calculateClusterCentroid (vector< geometry_msgs::Point > support_points)
 
PointPtr calculateClusterMedian (vector< PointPtr > support_points)
 Calculates the cluster's central point. More...
 
geometry_msgs::Point calculateClusterMedian (vector< geometry_msgs::Point > support_points)
 
double cosineDistance (vector< double > &vect1, vector< double > &vect2)
 Calculates the cosine distance between 2 vectors. More...
 
double deg2rad (double angle)
 Converts degree values to radian values. More...
 
int dietmayerClustering (vector< PointPtr > &points, double C0, vector< ClusterPtr > &clusters_Dietmayer)
 Performs Segmentation operation with the Dietmayer Segmentation Algorithm. More...
 
double euclideanDistance (geometry_msgs::Point &point1, geometry_msgs::Point &point2)
 
int nnClustering (vector< PointPtr > &points, double threshold, vector< ClusterPtr > &clusters_nn)
 Performs Segmentation operation with the Spacial Nerarest Neighbor Algorithm. More...
 
int premebidaClustering (vector< PointPtr > &points, double threshold_prem, vector< ClusterPtr > &clusters_Premebida)
 Performs Segmentation operation with the Multivariable Segmentation Algorithm. More...
 
vector< double > rangeFeatures (double range1, double range2, PointPtr range1cart, PointPtr range2cart)
 A auxiliary function of the premebidaClustering function Calculates the a set of atributes of a pair of laser points. More...
 
void recursiveClustering (vector< PointPtr > &points, vector< pair< ClusterPtr, bool > > &point_association, double threshold, uint idx)
 Auxiliary function to the nnClustering - Recursive function. More...
 
int santosClustering (vector< PointPtr > &points, double C0, double beta, vector< ClusterPtr > &clusters_Santos)
 Performs Segmentation operation with the Santos Approach from the Dietmayer Segmentation Algorithm. More...
 
int simpleClustering (vector< PointPtr > &points, double threshold, vector< ClusterPtr > &clusters)
 Performs a Simple Segmentation operation. More...
 

Detailed Description

Clustering related functions.

Author
Daniel Coimbra

Definition in file clustering.cpp.

Function Documentation

int abdClustering ( vector< PointPtr > &  points,
double  lambda,
vector< ClusterPtr > &  clusters_ABD 
)

Performs Segmentation operation with the Adaptative Breakpoint Detector.

Parameters
pointsincoming Laser Points
lamdaauxiliary parameter
clusters_ABDclusters output vector of clusters, these clusters use the Cluster class
Returns
Number of clusters resulted from the Adaptative Breakpoint Detector

Definition at line 384 of file clustering.cpp.

PointPtr calculateClusterCentroid ( vector< PointPtr support_points)

Calculates the cluster's centroid.

Parameters
support_pointscluster's support points
Returns
The coordinates of the cluster's centroid

Definition at line 702 of file clustering.cpp.

geometry_msgs::Point calculateClusterCentroid ( vector< geometry_msgs::Point >  support_points)

Definition at line 723 of file clustering.cpp.

PointPtr calculateClusterMedian ( vector< PointPtr support_points)

Calculates the cluster's central point.

Parameters
support_pointscluster's support points
Returns
The coordinates of the cluster's central point

Definition at line 747 of file clustering.cpp.

geometry_msgs::Point calculateClusterMedian ( vector< geometry_msgs::Point >  support_points)

Definition at line 782 of file clustering.cpp.

double cosineDistance ( vector< double > &  vect1,
vector< double > &  vect2 
)

Calculates the cosine distance between 2 vectors.

Parameters
vect1input vector with the range atributes from the fist pair
vect2input vector with the range atributes from the second pair
Returns
Cosine distance

Definition at line 665 of file clustering.cpp.

double deg2rad ( double  angle)

Converts degree values to radian values.

Parameters
angleangle value in degrees
Returns
angle value in radians

Definition at line 687 of file clustering.cpp.

int dietmayerClustering ( vector< PointPtr > &  points,
double  C0,
vector< ClusterPtr > &  clusters_Dietmayer 
)

Performs Segmentation operation with the Dietmayer Segmentation Algorithm.

Parameters
pointsincoming Laser Points
C0parameter used for noise reduction
clusters_Dietmayeroutput vector of clusters, these clusters use the Cluster class
Returns
Number of clusters resulted from the Dietmayer Segmentation Algorithm

Definition at line 144 of file clustering.cpp.

double euclideanDistance ( geometry_msgs::Point &  point1,
geometry_msgs::Point &  point2 
)

Definition at line 692 of file clustering.cpp.

int nnClustering ( vector< PointPtr > &  points,
double  threshold,
vector< ClusterPtr > &  clusters_nn 
)

Performs Segmentation operation with the Spacial Nerarest Neighbor Algorithm.

Parameters
pointsincoming Laser Points
thresholddistance value used to break clusters
clusters_nnclusters output vector of clusters, these clusters use the Cluster class
Returns
Number of clusters resulted from the Spacial Nerarest Neighbor Algorithm

Definition at line 468 of file clustering.cpp.

int premebidaClustering ( vector< PointPtr > &  points,
double  threshold_prem,
vector< ClusterPtr > &  clusters_Premebida 
)

Performs Segmentation operation with the Multivariable Segmentation Algorithm.

Parameters
pointsincoming Laser Points
threshold_premcosine distance value used to break clusters
clusters_Premebidaclusters output vector of clusters, these clusters use the Cluster class
Returns
Number of clusters resulted from the Multivariable Segmentation Algorithm

Definition at line 239 of file clustering.cpp.

vector<double> rangeFeatures ( double  range1,
double  range2,
PointPtr  range1cart,
PointPtr  range2cart 
)

A auxiliary function of the premebidaClustering function Calculates the a set of atributes of a pair of laser points.

Parameters
range1range value of the the first point
range2range value of the the second point
range1cartcartesian value of the first point
range2cartcartesian value of the second point
Returns
Vector of atributes

Definition at line 635 of file clustering.cpp.

void recursiveClustering ( vector< PointPtr > &  points,
vector< pair< ClusterPtr, bool > > &  point_association,
double  threshold,
uint  idx 
)

Auxiliary function to the nnClustering - Recursive function.

Parameters
pointsincoming Laser Points
point_associationpair with the output vector of clusters and its state of association
thresholddistance value used to break clusters
idxindex of the scan point
Returns
void

Definition at line 819 of file clustering.cpp.

int santosClustering ( vector< PointPtr > &  points,
double  C0,
double  beta,
vector< ClusterPtr > &  clusters_Santos 
)

Performs Segmentation operation with the Santos Approach from the Dietmayer Segmentation Algorithm.

Parameters
pointsincoming Laser Points
C0parameter used for noise reduction
betaparameter aiming to reduce the dependence of the segmentation with respect to the distance between the LRF and the objects
clusters_Santosclusters output vector of clusters, these clusters use the Cluster class
Returns
Number of clusters resulted from the Santos Approach from the Dietmayer Segmentation Algorithm

Definition at line 538 of file clustering.cpp.

int simpleClustering ( vector< PointPtr > &  points,
double  threshold,
vector< ClusterPtr > &  clusters 
)

Performs a Simple Segmentation operation.

Parameters
pointsincoming Laser Points
thresholddistance value used to break clusters
clustersoutput vector of clusters, these clusters use the Cluster class
Returns
Number of clusters resulted from the simple segmentation algorithm

Definition at line 49 of file clustering.cpp.



lidar_segmentation
Author(s): Daniel Coimbra
autogenerated on Mon Mar 2 2015 01:32:12