pmht.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 ***************************************************************************************************/
34 #include <ros/ros.h>
35 #include <mtt/tree.hh>
36 #include <mtt/tree_util.hh>
37 
38 #include <colormap/colormap.h>
39 
40 #include <laser_geometry/laser_geometry.h>
41 
42 #include <pcl/point_types.h>
43 #include <pcl/io/pcd_io.h>
44 #include <pcl/kdtree/kdtree_flann.h>
45 #include <pcl/surface/mls.h>
46 
47 #include <Eigen/Dense>
48 #include <Eigen/Cholesky>
49 
50 #include <visualization_msgs/Marker.h>
51 #include <visualization_msgs/MarkerArray.h>
52 
53 // #include <boost/lexical_cast.hpp>
54 // #include <boost/format.hpp>
55 
56 #include <graphviz/gvc.h>
57 #include <graphviz/types.h>
58 #include <graphviz/gvplugin.h>
59 
60 #include <mtt/types_declaration.h>
61 #include <mtt/graph_wrapper.h>
62 #include <mtt/mht.h>
63 
64 extern "C" {
65  extern void gvconfig_plugin_install_from_library(GVC_t*,char*,gvplugin_library_t*);
66 }
67 
68 using namespace std;
69 using namespace ros;
70 
71 
72 //Prototypes
73 
86 MatrixXd EllipseParametric(Matrix2d& cov,Vector2d& mu,double MahThreshold);
87 
91 void CreateMarkers(vector<visualization_msgs::Marker>& marker_vector,vector<t_clusterPtr>&clusters);
101 void PointCloud2ToVector(const sensor_msgs::PointCloud2& cloud,vector<t_pointPtr>& data);
102 
112 void CreateObjects(vector<t_pointPtr>&data,vector<t_clusterPtr>&clusters,double clustering_distance);
113 
123 double Mahalanobis(Vector2d&y,Vector2d&mean,Matrix2d& cov);
124 
133 double Mahalanobis_distance(t_nodePtr&node,t_clusterPtr&cluster);
134 
144 {
145  return sqrt( pow(node->x_p(0)-cluster->centroid.x,2) + pow(node->x_p(1)-cluster->centroid.y,2));
146 }
147 
157 {
158  return sqrt( pow(p1.x-p2.x,2) + pow(p1.y-p2.y,2));
159 }
160 
169 vector<t_clusterPtr>::iterator GetClosestCandidate(t_nodePtr&node,vector<t_clusterPtr>&clusters);
170 
void CreateMarkers(vector< visualization_msgs::Marker > &marker_vector, vector< t_clusterPtr > &clusters)
Create markers for Rviz.
Definition: pmht.cpp:379
double Euclidean_distance(t_nodePtr &node, t_clusterPtr &cluster)
Calculate the Euclidean distance from node to cluster.
Definition: pmht.h:143
boost::shared_ptr< t_node > t_nodePtr
Shared pointer to the t_node class.
void CreateObjects(vector< t_pointPtr > &data, vector< t_clusterPtr > &clusters, double clustering_distance)
This function converts a set of points into groups (aka clusters)
Definition: pmht.cpp:525
Header for type declaration, only constant velocity Kalman filter.
vector< t_clusterPtr >::iterator GetClosestCandidate(t_nodePtr &node, vector< t_clusterPtr > &clusters)
Get the closest candidate to the node from all the clusters.
Definition: pmht.cpp:601
double x
x coordinate (Cartesian)
void gvconfig_plugin_install_from_library(GVC_t *, char *, gvplugin_library_t *)
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...
Definition: pmht.cpp:464
double Mahalanobis_distance(t_nodePtr &node, t_clusterPtr &cluster)
Calculate the distance between a node and a cluster.
Definition: pmht.cpp:580
Mht implementation main header.
double y
y coordinate (Cartesian)
GVGraph class declaration.
boost::shared_ptr< t_cluster > t_clusterPtr
Shared pointer to the t_cluster class.
MatrixXd EllipseParametric(Matrix2d &cov, Vector2d &mu, double MahThreshold)
Create a parametric ellipse from covariance matrix.
Definition: pmht.cpp:125
Polar point structure.
Definition: mtt_common.h:126
double Mahalanobis(Vector2d &y, Vector2d &mean, Matrix2d &cov)
Calculate the Mahalanobis distance.
Definition: pmht.cpp:572


mtt
Author(s): Jorge Almeida
autogenerated on Mon Mar 2 2015 01:32:18