/home/laradmin/lar/perception/planarobstacles/lidar_segmentation/src/lidar_segmentation.h File Reference

Global include file. More...

#include "ros/ros.h"
#include "std_msgs/String.h"
#include <rosbag/bag.h>
#include <visualization_msgs/Marker.h>
#include <visualization_msgs/MarkerArray.h>
#include <tf/transform_broadcaster.h>
#include <sstream>
#include "sensor_msgs/LaserScan.h"
#include "geometry_msgs/Point.h"
#include <vector>
#include <iostream>
#include <stdlib.h>
#include <colormap/colormap.h>
#include <utility>
#include <map>
#include <fstream>
#include <string>
#include <ros/package.h>
#include "clustering.h"
#include "groundtruth.h"
Include dependency graph for lidar_segmentation.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  Point

Defines

#define ABD_SEG   4;
#define DIET_SEG   3;
#define NN_SEG   5;
#define PREM_SEG   2;
#define SANTOS_B_SEG   7;
#define SANTOS_C_SEG   6;
#define SIMPLE_SEG   1;

Typedefs

typedef boost::shared_ptr
< ::sensor_msgs::LaserScan > 
LaserScanPtr
typedef boost::shared_ptr< PointPointPtr

Functions

bool comparePoints (PointPtr p1, PointPtr p2)
 Comparison function.
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.
bool correctClusterId (PointPtr p, int cluster_id)
 Compares the point id to a cluster_id, if true that point is erased.
int createPointsFromFile (vector< PointPtr > &points, C_DataFromFilePtr data_gt)
 Creates a Point class from the file with the Ground-truth points.
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.
void removeInvalidPoints (vector< PointPtr > &laser_points, vector< ClusterPtr > clusters, uint min_points)
 Removes points belonging to clusters with less than min_points.
int writeResults_GT (uint iteration, vector< PointPtr > &points, int id_result)
 Wirtes properties of the Ground-truth segments into a text file.
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.

Detailed Description

Global include file.

Author:
Daniel Coimbra

Definition in file lidar_segmentation.h.


Define Documentation

#define ABD_SEG   4;

Definition at line 61 of file lidar_segmentation.h.

#define DIET_SEG   3;

Definition at line 60 of file lidar_segmentation.h.

#define NN_SEG   5;

Definition at line 62 of file lidar_segmentation.h.

#define PREM_SEG   2;

Definition at line 59 of file lidar_segmentation.h.

#define SANTOS_B_SEG   7;

Definition at line 64 of file lidar_segmentation.h.

#define SANTOS_C_SEG   6;

Definition at line 63 of file lidar_segmentation.h.

#define SIMPLE_SEG   1;

Definition at line 58 of file lidar_segmentation.h.


Typedef Documentation

typedef boost::shared_ptr< ::sensor_msgs::LaserScan> LaserScanPtr

Definition at line 102 of file lidar_segmentation.h.

typedef boost::shared_ptr<Point> PointPtr

Definition at line 101 of file lidar_segmentation.h.


Function Documentation

bool comparePoints ( PointPtr  p1,
PointPtr  p2 
)

Comparison function.

Parameters:
p1 first PointPtr input
p2 second PointPtr input
Returns:
the input with belonging to the lowest iteration and lowest label, else return false

Definition at line 163 of file groundtruth.cpp.

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.

Parameters:
scan_msg incoming LaserScan
points incoming Laser Points
clusters_GT output vector of clusters, these clusters use the Cluster class
Returns:
Number of clusters on the groundtruth
bool correctClusterId ( PointPtr  p,
int  cluster_id 
)

Compares the point id to a cluster_id, if true that point is erased.

Parameters:
p point to be compared
cluster_id id of the invalid cluster
Returns:
1 if point id = cluster id

Definition at line 42 of file main.cpp.

int createPointsFromFile ( vector< PointPtr > &  points,
C_DataFromFilePtr  data_gt 
)

Creates a Point class from the file with the Ground-truth points.

Parameters:
points incoming Laser Points
data_gts output x, y and labels from one iteration, it uses the C_DataFromFile class
Returns:
return 0

Definition at line 1272 of file main.cpp.

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.

Parameters:
points_in incoming Laser Points
points_out points with range between the minimum and maximum value
min_range minimum range for a point to be considered valid
max_range maximum range for a point to be considered valid
Returns:
void

Definition at line 47 of file main.cpp.

void removeInvalidPoints ( vector< PointPtr > &  laser_points,
vector< ClusterPtr clusters,
uint  min_points 
)

Removes points belonging to clusters with less than min_points.

Parameters:
laser_points incoming Laser Points
clusters clusters input vector of clusters, these clusters use the Cluster class
min_points clusters with points less than this value are removed
Returns:
void

Definition at line 72 of file main.cpp.

int writeResults_GT ( uint  iteration,
vector< PointPtr > &  points,
int  id_result 
)

Wirtes properties of the Ground-truth segments into a text file.

Parameters:
iteration iteration of the Laser Scan
points incoming Laser Points
id_result if id_result == 1 writes segments' boundaries; else writes segments' centers
Returns:
return 0

Definition at line 222 of file main.cpp.

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.

Parameters:
points incoming Laser Points
algorithm_id case 1 - Simple Segmentation; case 2 - Multivariable Segmentation; case 3 - Dietmayer Segmentation; case 4 - Adaptive Breakpoint Detector; case 5 - Spatital Nearest Neigbour; case 6 - Santos Approach C0 variation; case 7 - Santos Approach Beta variation;
initial_value Initial value of the threshold parameter;
increment Increment of the threshold parameter;
number_of_iterations Number of threshold variations
iteration iteration of the Lasr Scan
id_result if id_result == 1 writes segments' boundaries; else writes segments' centers
Returns:
return 0

Definition at line 349 of file main.cpp.

 All Classes Files Functions Variables Typedefs Defines


lidar_segmentation
Author(s): Daniel
autogenerated on Wed Jul 23 04:34:28 2014