clustering.h
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
33 #ifndef _COIMBRA_CLUSTERING_H_
34 #define _COIMBRA_CLUSTERING_H_
35 
36 #include <vector>
37 #include "geometry_msgs/Point.h"
38 #include "sensor_msgs/LaserScan.h"
39 
40 using namespace std;
41 
42 class Point;
43 typedef boost::shared_ptr<Point> PointPtr;
44 
45 
54 class Cluster
55 {
56 public:
57  int id;
63  vector<double> ranges;
65  vector<PointPtr> support_points;
66 };
67 
68 
69 //Shared pointer to the Cluster class
70 typedef boost::shared_ptr<Cluster> ClusterPtr;
71 
72 /* Clustering functions */
73 
82 int simpleClustering(vector<PointPtr>& points, double threshold, vector<ClusterPtr>& clusters);
83 
92 int dietmayerClustering( vector<PointPtr>& points, double C0 ,vector<ClusterPtr>& clusters_Dietmayer);
93 
102 int premebidaClustering( vector<PointPtr>& points, double threshold_prem , vector<ClusterPtr>& clusters_Premebida);
103 
112 int abdClustering( vector<PointPtr>& points , double lambda ,vector<ClusterPtr>& clusters_ABD);
113 
122 int nnClustering( vector<PointPtr>& points, double threshold , vector<ClusterPtr>& clusters_nn);
123 
133 int santosClustering( vector<PointPtr>& points, double C0, double beta, vector<ClusterPtr>& clusters_Santos);
134 
145 vector<double> rangeFeatures( double range1, double range2, PointPtr range1cart, PointPtr range2cart);
146 
154 double cosineDistance(vector<double>& vect1, vector<double>& vect2);
155 
162 double deg2rad(double angle);
163 
164 
171 PointPtr calculateClusterCentroid( vector<PointPtr> support_points );
172 
179 PointPtr calculateClusterMedian(vector<PointPtr> support_points);
180 
181 #endif
PointPtr centroid
Definition: clustering.h:59
double deg2rad(double angle)
Converts degree values to radian values.
Definition: clustering.cpp:687
vector< double > ranges
Definition: clustering.h:63
boost::shared_ptr< Point > PointPtr
Definition: clustering.h:42
double cosineDistance(vector< double > &vect1, vector< double > &vect2)
Calculates the cosine distance between 2 vectors.
Definition: clustering.cpp:665
int abdClustering(vector< PointPtr > &points, double lambda, vector< ClusterPtr > &clusters_ABD)
Performs Segmentation operation with the Adaptative Breakpoint Detector.
Definition: clustering.cpp:384
boost::shared_ptr< Cluster > ClusterPtr
Definition: clustering.h:70
int nnClustering(vector< PointPtr > &points, double threshold, vector< ClusterPtr > &clusters_nn)
Performs Segmentation operation with the Spacial Nerarest Neighbor Algorithm.
Definition: clustering.cpp:468
vector< PointPtr > support_points
Definition: clustering.h:65
int simpleClustering(vector< PointPtr > &points, double threshold, vector< ClusterPtr > &clusters)
Performs a Simple Segmentation operation.
Definition: clustering.cpp:49
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 ...
Definition: clustering.cpp:635
PointPtr calculateClusterCentroid(vector< PointPtr > support_points)
Calculates the cluster's centroid.
Definition: clustering.cpp:702
int premebidaClustering(vector< PointPtr > &points, double threshold_prem, vector< ClusterPtr > &clusters_Premebida)
Performs Segmentation operation with the Multivariable Segmentation Algorithm.
Definition: clustering.cpp:239
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...
Definition: clustering.cpp:538
PointPtr calculateClusterMedian(vector< PointPtr > support_points)
Calculates the cluster's central point.
Definition: clustering.cpp:747
int id
Definition: clustering.h:57
int dietmayerClustering(vector< PointPtr > &points, double C0, vector< ClusterPtr > &clusters_Dietmayer)
Performs Segmentation operation with the Dietmayer Segmentation Algorithm.
Definition: clustering.cpp:144
PointPtr central_point
Definition: clustering.h:61


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