lidar_segmentation.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_LIDAR_SEGMENTATION_H_
34 #define _COIMBRA_LIDAR_SEGMENTATION_H_
35 
36 #include "ros/ros.h"
37 #include "std_msgs/String.h"
38 #include <rosbag/bag.h>
39 #include <visualization_msgs/Marker.h>
40 #include <visualization_msgs/MarkerArray.h>
41 #include <tf/transform_broadcaster.h>
42 #include <sstream>
43 #include "sensor_msgs/LaserScan.h"
44 #include "geometry_msgs/Point.h"
45 #include <vector>
46 #include <iostream>
47 #include <stdlib.h>
48 #include <colormap/colormap.h>
49 #include <utility>
50 #include <map>
51 #include <fstream>
52 #include <string>
53 #include <ros/package.h>
54 #include "clustering.h"
55 #include "groundtruth.h"
56 
57 
58 # define SIMPLE_SEG 1;
59 # define PREM_SEG 2;
60 # define DIET_SEG 3;
61 # define ABD_SEG 4;
62 # define NN_SEG 5;
63 # define SANTOS_C_SEG 6;
64 # define SANTOS_B_SEG 7;
65 
66 using namespace std;
67 
68 
77 class Point
78 {
79  public:
80 
82  {
83  x=0;
84  y=0;
85  theta=0;
86  range=0;
87  label=0;
88  iteration=0;
89  }
90 
91  double x;
92  double y;
93  double theta;
94  double range;
95  int label;
96  int cluster_id;
97  int iteration;
98 };
99 
100 //Shared pointer to the Point class
101 typedef boost::shared_ptr<Point> PointPtr;
102 typedef boost::shared_ptr< ::sensor_msgs::LaserScan> LaserScanPtr;
103 
104 
112 bool comparePoints(PointPtr p1,PointPtr p2);
113 
122 int convertPointsToCluster( const sensor_msgs::LaserScan::ConstPtr& scan_msg , vector<PointPtr>& points, vector<ClusterPtr>& clusters_GT);
123 
131 int createPointsFromFile( vector<PointPtr>& points , C_DataFromFilePtr data_gt );
132 
133 
143 void filterPoints(vector<PointPtr>& points_in , vector<PointPtr>& points_out, double min_range, double max_range);
144 
145 
153 void removeInvalidPoints(vector<PointPtr>& laser_points, vector<ClusterPtr> clusters, uint min_points );
154 
155 
163 bool correctClusterId (PointPtr p, int cluster_id);
164 
165 
174 int writeResults_GT(uint iteration , vector<PointPtr>& points , int id_result);
175 
176 
195 int writeResults_paths(vector<PointPtr>& points, int algorithm_id, double initial_value, double increment, int number_of_iterations , uint iteration, int id_result);
196 
197 
198 #endif
double range
bool correctClusterId(PointPtr p, int cluster_id)
Compares the point id to a cluster_id, if true that point is erased.
Definition: main.cpp:42
int createPointsFromFile(vector< PointPtr > &points, C_DataFromFilePtr data_gt)
Creates a Point class from the file with the Ground-truth points.
Definition: main.cpp:1272
boost::shared_ptr< Point > PointPtr
Definition: clustering.h:42
double theta
Clustering related functions header.
void removeInvalidPoints(vector< PointPtr > &laser_points, vector< ClusterPtr > clusters, uint min_points)
Removes points belonging to clusters with less than min_points.
Definition: main.cpp:72
bool comparePoints(PointPtr p1, PointPtr p2)
Comparison function.
void filterPoints(vector< PointPtr > &points_in, vector< PointPtr > &points_out, double min_range, double max_range)
Function that outputs a set of points with range between min_range and max_range values.
Definition: main.cpp:47
int writeResults_paths(vector< PointPtr > &points, int algorithm_id, double initial_value, double increment, int number_of_iterations, uint iteration, int id_result)
Wirtes properties of the Algorithms segments into a text file.
Definition: main.cpp:349
boost::shared_ptr< C_DataFromFile > C_DataFromFilePtr
Definition: groundtruth.h:62
int convertPointsToCluster(const sensor_msgs::LaserScan::ConstPtr &scan_msg, vector< PointPtr > &points, vector< ClusterPtr > &clusters_GT)
Convert the all Point class from a scan to a Cluster class.
int writeResults_GT(uint iteration, vector< PointPtr > &points, int id_result)
Wirtes properties of the Ground-truth segments into a text file.
Definition: main.cpp:222
Groundtruth related functions header.
boost::shared_ptr< ::sensor_msgs::LaserScan > LaserScanPtr
boost::shared_ptr< Point > PointPtr


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