/home/laradmin/lar/perception/planarobstacles/mtt/include/mtt/pmht.h File Reference

Header for the Multi-Hypothesis Tracking data association algorithm. More...

#include <ros/ros.h>
#include <mtt/tree.hh>
#include <mtt/tree_util.hh>
#include <colormap/colormap.h>
#include <laser_geometry/laser_geometry.h>
#include <pcl/point_types.h>
#include <pcl/io/pcd_io.h>
#include <pcl/kdtree/kdtree_flann.h>
#include <pcl/surface/mls.h>
#include <Eigen/Dense>
#include <Eigen/Cholesky>
#include <visualization_msgs/Marker.h>
#include <visualization_msgs/MarkerArray.h>
#include <graphviz/gvc.h>
#include <graphviz/types.h>
#include <stdio.h>
#include <assert.h>
#include <signal.h>
#include "geom.h"
#include "gvcext.h"
#include "pathgeom.h"
#include "textpara.h"
#include <cgraph.h>
#include "usershape.h"
#include <mtt/types_declaration.h>
#include <mtt/graph_wrapper.h>
#include <mtt/mht.h>
Include dependency graph for pmht.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Functions

void CreateMarkers (vector< visualization_msgs::Marker > &marker_vector, vector< t_clusterPtr > &clusters)
 Create markers for Rviz.
void CreateObjects (vector< t_pointPtr > &data, vector< t_clusterPtr > &clusters, double clustering_distance)
 This function converts a set of points into groups (aka clusters).
MatrixXd EllipseParametric (Matrix2d &cov, Vector2d &mu, double MahThreshold)
 Create a parametric ellipse from covariance matrix.
double Euclidean_distance (t_point &p1, t_point &p2)
 Calculate the Euclidean distance from point to point.
double Euclidean_distance (t_nodePtr &node, t_clusterPtr &cluster)
 Calculate the Euclidean distance from node to cluster.
vector< t_clusterPtr >::iterator GetClosestCandidate (t_nodePtr &node, vector< t_clusterPtr > &clusters)
 Get the closest candidate to the node from all the clusters.
void gvconfig_plugin_install_from_library (GVC_t *, char *, gvplugin_library_t *)
double Mahalanobis (Vector2d &y, Vector2d &mean, Matrix2d &cov)
 Calculate the Mahalanobis distance.
double Mahalanobis_distance (t_nodePtr &node, t_clusterPtr &cluster)
 Calculate the distance between a node and a cluster.
void PointCloud2ToVector (const sensor_msgs::PointCloud2 &cloud, vector< t_pointPtr > &data)
 Convert from a point cloud representation to a stl vector of shared pointers to the class t_point.

Detailed Description

Header for the Multi-Hypothesis Tracking data association algorithm.

For additional info on the Mht algorithm check here.

Definition in file pmht.h.


Function Documentation

void CreateMarkers ( vector< visualization_msgs::Marker > &  marker_vector,
vector< t_clusterPtr > &  clusters 
)

Create markers for Rviz.

Definition at line 379 of file pmht.cpp.

void CreateObjects ( vector< t_pointPtr > &  data,
vector< t_clusterPtr > &  clusters,
double  clustering_distance 
)

This function converts a set of points into groups (aka clusters).

The clustering algorithm is solely based on the distance between consecutive points in the polar grid.
It copies the support points of the cluster into the own cluster so no reference to the original data is needed not even desired.

Parameters:
data vector of data
clusters vector of clusters (this is the output so it will be filled)
clustering_distance maximum distance between two points for them to be in the same cluster

Definition at line 525 of file pmht.cpp.

MatrixXd EllipseParametric ( Matrix2d &  cov,
Vector2d &  mu,
double  MahThreshold 
)

Create a parametric ellipse from covariance matrix.

This function creates a parametric ellipse from a covariance matrix, the mean values and a threshold. The main axes directions are calculated using the eigenvectors of the covariance matrix, then a crawling algorithm detects the threshold points obtaining the lengths of the axes. After that the generic parametric equation is used to calculate points in the threshold boundary.

Parameters:
cov covariance matrix
mu mean values
MahThreshold Mahalanobis threshold to use
Returns:
the xy points of the ellipse, the last points is equal to the first so the ellipse closes

Definition at line 125 of file pmht.cpp.

double Euclidean_distance ( t_point p1,
t_point p2 
)

Calculate the Euclidean distance from point to point.

Calculate the euclidean distance from a point to a point

Parameters:
p1 point 1
p2 point 2
Returns:
the euclidean distance

Definition at line 156 of file pmht.h.

double Euclidean_distance ( t_nodePtr node,
t_clusterPtr cluster 
)

Calculate the Euclidean distance from node to cluster.

Calculate the euclidean distance from a node and a cluster.

Parameters:
node Node, the coordinates in x_p point of the node will be used
cluster Cluster, the centroid coordinates will be used
Returns:
the euclidean distance

Definition at line 143 of file pmht.h.

vector<t_clusterPtr>::iterator GetClosestCandidate ( t_nodePtr node,
vector< t_clusterPtr > &  clusters 
)

Get the closest candidate to the node from all the clusters.

This function calls the CalculateDistance function to do the real node to cluster evaluation.

Parameters:
node node to use
clusters clusters to search
Returns:
iterator to a member of the clusters

Definition at line 601 of file pmht.cpp.

void gvconfig_plugin_install_from_library ( GVC_t *  ,
char *  ,
gvplugin_library_t *   
)
double Mahalanobis ( Vector2d &  y,
Vector2d &  mean,
Matrix2d &  cov 
)

Calculate the Mahalanobis distance.

Calculate the Mahalanobis distance for a measurement y from a set with a given mean and covariance.

Parameters:
y measurement
mean mean value of the variable
cov covariance of the variable
Returns:
the Mahalanobis distance

Definition at line 572 of file pmht.cpp.

double Mahalanobis_distance ( t_nodePtr node,
t_clusterPtr cluster 
)

Calculate the distance between a node and a cluster.

This function uses the Mahalanobis distance between the node position estimation and the cluster position.

Parameters:
node tree node to use
cluster cluster to use
Returns:
the Mahalanobis distance

Definition at line 580 of file pmht.cpp.

void PointCloud2ToVector ( const sensor_msgs::PointCloud2 &  cloud,
vector< t_pointPtr > &  data 
)

Convert from a point cloud representation to a stl vector of shared pointers to the class t_point.

This function first puts all the points in a polar grid representation and reorders them to be angularly sequenced.
This function has an important parameter which is the angular resolution of the grid that should be a ros param.

Todo:
Convert the current hard coded angular resolution of the grid (vulgar grid spacing).
Parameters:
cloud input point cloud
data stl vector of boost::shared_ptr of the class t_point

Definition at line 464 of file pmht.cpp.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


mtt
Author(s): Jorge Almeida
autogenerated on Wed Jul 23 04:34:57 2014