groundtruth.cpp
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 #include "lidar_segmentation.h"
34 #include "clustering.h"
35 #include "groundtruth.h"
36 
37 //read from the ground truth file
38 int readDataFile( vector<C_DataFromFilePtr>& data_gts , int values_per_scan)
39 {
40 
41  string path = ros::package::getPath("roslib");
42  ifstream source("src/gt_datas/GT_NEW_DIV.txt"); // build a read-Stream
43 
44  if (!source.is_open())
45  {
46  cout << "Couldn't open the GT_NEW file" << endl;
47  return 1;
48  }
49 
50  string line;
51 
52  while(source.good()) //read stream line by line
53  {
54  getline(source, line); //Get iteration
55 
56  if(line[0]!='i')
57  continue;
58 
59  int it;
60 
61  //New iteration
62  sscanf(line.c_str(),"%*c %d",&it);
63 
64  C_DataFromFilePtr data_gt(new C_DataFromFile);
65 
66  data_gt->iteration = it;
67 
68  getline(source ,line); //get x values
69 
70  int c = 0;
71  double x , y;
72  int label;
73 
74  const char*ptr = line.c_str();
75 
76  while(c < values_per_scan)
77  {
78  sscanf(ptr,"%lf", &x); //scans values
79 
80  data_gt->x_valuesf.push_back(x);
81 
82  c++;
83 
84  ptr = strstr(ptr, " "); //seeks for " "
85 
86  if(ptr==NULL)
87  break;
88 
89  ptr++;
90  }
91 
92 //----------------------------------------------------------------------------
93 // for(uint j=0;j< data_gt->x_valuesf.size();j++)
94 // {
95 // cout<<"x_valuesf: "<< data_gt->x_valuesf[j]<<endl;
96 // }
97 //----------------------------------------------------------------------------
98 
99  getline(source , line); //get y values
100  const char*ptr2 = line.c_str();
101  c = 0;
102 
103  while(c < values_per_scan)
104  {
105  sscanf(ptr2, "%lf" , &y);
106 
107  data_gt->y_valuesf.push_back(y);
108  c++;
109 
110  ptr2 = strstr(ptr2, " "); //seeks for " "
111 
112  if(ptr2==NULL)
113  break;
114 
115  ptr2++;
116  }
117 
118 //----------------------------------------------------------------------------
119 // for(uint j=0;j< data_gt->x_valuesf.size();j++)
120 // {
121 // cout<<"y_valuesf: "<< data_gt->y_valuesf[j]<<endl;
122 // }
123 //----------------------------------------------------------------------------
124 
125  getline(source , line); //labels
126  const char*ptr3 = line.c_str();
127  c = 0;
128 
129  while(c < values_per_scan)
130  {
131  sscanf(ptr3, "%d" , &label);
132 
133  data_gt->labels.push_back(label);
134  c++;
135 
136  ptr3 = strstr(ptr3, " "); //seeks for " "
137 
138  if(ptr3==NULL)
139  break;
140 
141  ptr3++;
142  }
143 
144 //----------------------------------------------------------------------------
145 // for(uint j=0; j< data_gt->x_valuesf.size(); j++)
146 // {
147 // cout<<"labels : "<< data_gt->labels[j] <<endl;
148 // }
149 //----------------------------------------------------------------------------
150 
151  data_gts.push_back(data_gt);
152 
153  } //end while
154 
155  cout<<"close file"<<endl;
156  source.close();
157 
158  return 0;
159 
160 } //end function
161 
162 
164 {
165  return p1->cluster_id < p2->cluster_id; //ascending order
166 }
167 
168 int convertPointsToCluster(vector<PointPtr>& points, vector<ClusterPtr>& clusters_GT)
169 {
170 
171  ClusterPtr cluster_gt(new Cluster);
172 
173  //add the first value
174  if( points[0]->label != 0 )
175  {
176  PointPtr p(new Point);
177  p->x = points[0]->x;
178  p->y = points[0]->y;
179  p->label = points[0]->label;
180  p->cluster_id = points[0]->cluster_id;
181 
182  cluster_gt->support_points.push_back(p);
183  cluster_gt->centroid = calculateClusterCentroid( cluster_gt->support_points );
184  cluster_gt->central_point = calculateClusterMedian(cluster_gt->support_points);
185  cluster_gt->id = p->cluster_id;
186  }
187 
188 
189  //For every line in the file
190  for(uint idx = 1; idx < points.size(); idx++ )
191  {
192  if(points[idx]->cluster_id== 0)
193  continue;
194 
195  if( (points[idx]->cluster_id != points[idx-1]->cluster_id))
196  {
197 
198  if(cluster_gt->support_points.size()>0)
199  clusters_GT.push_back(cluster_gt);
200 
201  //make cluster point to a new Cluster.
202  cluster_gt.reset(new Cluster);
203 
204  PointPtr p(new Point);
205  p->x = points[idx]->x;
206  p->y = points[idx]->y;
207  p->label = points[idx]->label;
208  p->cluster_id = points[idx]->cluster_id;
209 
210  cluster_gt->support_points.push_back(p);
211  cluster_gt->centroid = calculateClusterCentroid( cluster_gt->support_points );
212  cluster_gt->central_point = calculateClusterMedian(cluster_gt->support_points);
213  cluster_gt->id = p->cluster_id;
214 
215  }else
216  {
217  PointPtr p(new Point);
218  p->x = points[idx]->x;
219  p->y = points[idx]->y;
220  p->label = points[idx]->label;
221  p->cluster_id = points[idx]->cluster_id;
222 
223  cluster_gt->support_points.push_back(p);
224 
225  cluster_gt->centroid = calculateClusterCentroid( cluster_gt->support_points );
226  cluster_gt->central_point = calculateClusterMedian(cluster_gt->support_points);
227  cluster_gt->id = p->cluster_id;
228  }
229 
230  } //end for
231 
232  if(cluster_gt->support_points.size()>0)
233  clusters_GT.push_back(cluster_gt);
234 
235  cout<< "Clusters GT " << clusters_GT.size() << endl;
236 
237  return clusters_GT.size();
238 }
PointPtr calculateClusterCentroid(vector< PointPtr > support_points)
Calculates the cluster's centroid.
Definition: clustering.cpp:702
int convertPointsToCluster(vector< PointPtr > &points, vector< ClusterPtr > &clusters_GT)
Performs Segmentation operation with the Adaptative Breakpoint Detector.
bool comparePoints(PointPtr p1, PointPtr p2)
Comparison function.
boost::shared_ptr< Point > PointPtr
Definition: clustering.h:42
Clustering related functions header.
PointPtr calculateClusterMedian(vector< PointPtr > support_points)
Calculates the cluster's central point.
Definition: clustering.cpp:747
boost::shared_ptr< Cluster > ClusterPtr
Definition: clustering.h:70
int readDataFile(vector< C_DataFromFilePtr > &data_gts, int values_per_scan)
Reads from a file the x, y and labels values from all the laser points from one iteration.
Definition: groundtruth.cpp:38
boost::shared_ptr< C_DataFromFile > C_DataFromFilePtr
Definition: groundtruth.h:62
Global include file.
Groundtruth related functions header.


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