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
00034 #include <ros/ros.h>
00035 #include <mtt/tree.hh>
00036 #include <mtt/tree_util.hh>
00037
00038 #include <colormap/colormap.h>
00039
00040 #include <laser_geometry/laser_geometry.h>
00041
00042 #include <pcl/point_types.h>
00043 #include <pcl/io/pcd_io.h>
00044 #include <pcl/kdtree/kdtree_flann.h>
00045 #include <pcl/surface/mls.h>
00046
00047 #include <Eigen/Dense>
00048 #include <Eigen/Cholesky>
00049
00050 #include <visualization_msgs/Marker.h>
00051 #include <visualization_msgs/MarkerArray.h>
00052
00053
00054
00055
00056 #include <graphviz/gvc.h>
00057 #include <graphviz/types.h>
00058 #include <graphviz/gvplugin.h>
00059
00060 #include <mtt/types_declaration.h>
00061 #include <mtt/graph_wrapper.h>
00062 #include <mtt/mht.h>
00063
00064 extern "C" {
00065 extern void gvconfig_plugin_install_from_library(GVC_t*,char*,gvplugin_library_t*);
00066 }
00067
00068 using namespace std;
00069 using namespace ros;
00070
00071
00072
00073
00086 MatrixXd EllipseParametric(Matrix2d& cov,Vector2d& mu,double MahThreshold);
00087
00091 void CreateMarkers(vector<visualization_msgs::Marker>& marker_vector,vector<t_clusterPtr>&clusters);
00101 void PointCloud2ToVector(const sensor_msgs::PointCloud2& cloud,vector<t_pointPtr>& data);
00102
00112 void CreateObjects(vector<t_pointPtr>&data,vector<t_clusterPtr>&clusters,double clustering_distance);
00113
00123 double Mahalanobis(Vector2d&y,Vector2d&mean,Matrix2d& cov);
00124
00133 double Mahalanobis_distance(t_nodePtr&node,t_clusterPtr&cluster);
00134
00143 double Euclidean_distance(t_nodePtr&node,t_clusterPtr&cluster)
00144 {
00145 return sqrt( pow(node->x_p(0)-cluster->centroid.x,2) + pow(node->x_p(1)-cluster->centroid.y,2));
00146 }
00147
00156 double Euclidean_distance(t_point&p1,t_point&p2)
00157 {
00158 return sqrt( pow(p1.x-p2.x,2) + pow(p1.y-p2.y,2));
00159 }
00160
00169 vector<t_clusterPtr>::iterator GetClosestCandidate(t_nodePtr&node,vector<t_clusterPtr>&clusters);
00170