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 
00032 #ifndef _MHT_H_
00033 #define _MHT_H_
00034 
00035 #include <ros/ros.h>
00036 
00037 #include <visualization_msgs/MarkerArray.h>
00038 
00039 #include <mtt/graph_wrapper.h>
00040 
00041 #include <mtt/mht_declaration.h>
00042 
00043 #include <mtt/k_best.h>
00044 #include <mtt/cluster.h>
00045 
00046 #include <laser_geometry/laser_geometry.h>
00047 
00048 #include <pcl/point_types.h>
00049 #include <pcl/io/pcd_io.h>
00050 #include <pcl/kdtree/kdtree_flann.h>
00051 #include <pcl/surface/mls.h>
00052 
00053 #include <Eigen/Dense>
00054 #include <Eigen/Cholesky>
00055 
00056 #include <iostream>
00057 #include <istream>
00058 #include <fstream>
00059 #include <string>
00060 #include <complex>
00061 
00062 #include <boost/thread/thread.hpp>
00063 
00064 using Eigen::Vector4d;
00065 
00067 extern gvplugin_library_t gvplugin_xgtk_LTX_library;
00068 
00069 extern "C" 
00070 {
00074         extern void gvconfig_plugin_install_from_library(GVC_t*,char*,gvplugin_library_t*);
00075 }
00076 
00082 class Markers
00083 {
00084         public:
00092                 void update(visualization_msgs::Marker& marker);
00093                 
00097                 void decrement(void);
00098                 
00102                 void clean(void);
00103                 
00109                 vector<visualization_msgs::Marker> getOutgoingMarkers(void);
00110         private:
00112                 vector<visualization_msgs::Marker> markers;
00113 };
00114 
00123 vector<visualization_msgs::Marker> createTargetMarkers(vector<TargetPtr>& targets);
00124 
00133 vector<visualization_msgs::Marker> createClustersMarkers(vector<MeasurementPtr>& clusters);
00134 
00142 std_msgs::ColorRGBA makeColor(int id);
00143 
00154 std_msgs::ColorRGBA makeColor(double r,double g, double b, double a);
00155 
00165 geometry_msgs::Point makePose(double x,double y, double z);
00166 
00172 void dataHandler(const sensor_msgs::PointCloud2& msg);
00173 
00182 void* graphicalThread(void*data);
00183 
00193 void createObjects(vector<PointPtr>&data,vector<MeasurementPtr>&clusters,double clustering_distance);
00194 
00202 void pointCloud2ToVector(const sensor_msgs::PointCloud2& cloud,vector<PointPtr>& data);
00203 
00213 double euclideanDistance(Point&p1,Point&p2);
00214 
00215 #endif