00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00033 #ifndef _COIMBRA_LIDAR_SEGMENTATION_H_
00034 #define _COIMBRA_LIDAR_SEGMENTATION_H_
00035
00036 #include "ros/ros.h"
00037 #include "std_msgs/String.h"
00038 #include <rosbag/bag.h>
00039 #include <visualization_msgs/Marker.h>
00040 #include <visualization_msgs/MarkerArray.h>
00041 #include <tf/transform_broadcaster.h>
00042 #include <sstream>
00043 #include "sensor_msgs/LaserScan.h"
00044 #include "geometry_msgs/Point.h"
00045 #include <vector>
00046 #include <iostream>
00047 #include <stdlib.h>
00048 #include <colormap/colormap.h>
00049 #include <utility>
00050 #include <map>
00051 #include <fstream>
00052 #include <string>
00053 #include <ros/package.h>
00054 #include "clustering.h"
00055 #include "groundtruth.h"
00056
00057
00058 # define SIMPLE_SEG 1;
00059 # define PREM_SEG 2;
00060 # define DIET_SEG 3;
00061 # define ABD_SEG 4;
00062 # define NN_SEG 5;
00063 # define SANTOS_C_SEG 6;
00064 # define SANTOS_B_SEG 7;
00065
00066 using namespace std;
00067
00068
00077 class Point
00078 {
00079 public:
00080
00081 Point()
00082 {
00083 x=0;
00084 y=0;
00085 theta=0;
00086 range=0;
00087 label=0;
00088 iteration=0;
00089 }
00090
00091 double x;
00092 double y;
00093 double theta;
00094 double range;
00095 int label;
00096 int cluster_id;
00097 int iteration;
00098 };
00099
00100
00101 typedef boost::shared_ptr<Point> PointPtr;
00102 typedef boost::shared_ptr< ::sensor_msgs::LaserScan> LaserScanPtr;
00103
00104
00112 bool comparePoints(PointPtr p1,PointPtr p2);
00113
00122 int convertPointsToCluster( const sensor_msgs::LaserScan::ConstPtr& scan_msg , vector<PointPtr>& points, vector<ClusterPtr>& clusters_GT);
00123
00131 int createPointsFromFile( vector<PointPtr>& points , C_DataFromFilePtr data_gt );
00132
00133
00143 void filterPoints(vector<PointPtr>& points_in , vector<PointPtr>& points_out, double min_range, double max_range);
00144
00145
00153 void removeInvalidPoints(vector<PointPtr>& laser_points, vector<ClusterPtr> clusters, uint min_points );
00154
00155
00163 bool correctClusterId (PointPtr p, int cluster_id);
00164
00165
00174 int writeResults_GT(uint iteration , vector<PointPtr>& points , int id_result);
00175
00176
00195 int writeResults_paths(vector<PointPtr>& points, int algorithm_id, double initial_value, double increment, int number_of_iterations , uint iteration, int id_result);
00196
00197
00198 #endif