Go to the documentation of this file.00001 #ifndef EUCLIDEAN_CLUSTER_H
00002 #define EUCLIDEAN_CLUSTER_H
00003
00004 #include <fstream>
00005 #include <iostream>
00006 #include <sstream>
00007 #include <string>
00008
00009 #include <ros/ros.h>
00010 #include <sensor_msgs/PointCloud2.h>
00011 #include <std_msgs/Bool.h>
00012 #include <std_msgs/Float32.h>
00013
00014 #include <tf/transform_broadcaster.h>
00015 #include <tf/transform_datatypes.h>
00016 #include <tf/transform_listener.h>
00017
00018 #include <pcl/ModelCoefficients.h>
00019 #include <pcl/features/moment_of_inertia_estimation.h>
00020 #include <pcl/features/normal_3d.h>
00021 #include <pcl/filters/approximate_voxel_grid.h>
00022 #include <pcl/filters/crop_box.h>
00023 #include <pcl/filters/extract_indices.h>
00024 #include <pcl/filters/passthrough.h>
00025 #include <pcl/filters/statistical_outlier_removal.h>
00026 #include <pcl/filters/voxel_grid.h>
00027 #include <pcl/io/io.h>
00028 #include <pcl/io/pcd_io.h>
00029 #include <pcl/kdtree/kdtree.h>
00030 #include <pcl/point_types.h>
00031 #include <pcl/registration/ndt.h>
00032 #include <pcl/sample_consensus/method_types.h>
00033 #include <pcl/sample_consensus/model_types.h>
00034 #include <pcl/segmentation/extract_clusters.h>
00035 #include <pcl/segmentation/sac_segmentation.h>
00036 #include <pcl_conversions/pcl_conversions.h>
00037 #include <pcl_ros/impl/transforms.hpp>
00038
00039 #include <opencv/cv.h>
00040 #include <opencv2/imgproc/imgproc.hpp>
00041
00042 #include <jsk_recognition_msgs/BoundingBoxArray.h>
00043
00044 #include "../src/libsvm/svm.h"
00045
00046 using namespace pcl;
00047
00048 class EuclideanCluster {
00049 public:
00050 EuclideanCluster(ros::NodeHandle nh, ros::NodeHandle n);
00051 void EuclideanCallback(const sensor_msgs::PointCloud2::ConstPtr &source_pc);
00052 void CropBox(pcl::PointCloud<pcl::PointXYZI>::Ptr cloud, pcl::PointXYZ min, pcl::PointXYZ max);
00053 void Clustering(pcl::PointCloud<pcl::PointXYZI>::Ptr cloud);
00054 void read_scaling_parameters(std::string scaling_parameter_file);
00055 void normlize_features(svm_node *features);
00056 void feature_calculation(pcl::PointCloud<pcl::PointXYZI>::Ptr cloud,
00057 svm_node *features);
00058 jsk_recognition_msgs::BoundingBox MinAreaRect(pcl::PointCloud<pcl::PointXYZI>::Ptr cloud, int cluster_cnt);
00059 void run();
00060 std::vector<std::string> split(const std::string &s, char delim);
00061
00062 private:
00063 ros::NodeHandle nh_;
00064 ros::Rate rate_;
00065 std::string frame_id_;
00066 ros::Publisher fileterd_cloud_pub_;
00067 ros::Publisher euclidean_cluster_pub_;
00068 ros::Subscriber source_pc_sub_;
00069 tf::TransformListener tf_;
00070 tf::TransformBroadcaster br_;
00071
00072
00073 double clusterTolerance_;
00074 int minSize_;
00075 int maxSize_;
00076
00077 pcl::PointXYZ crop_min_, crop_max_;
00078
00079 std::string svm_model_path_;
00080 std::string svm_range_path_;
00081 svm_model *model_;
00082 std::vector<float> feature_max_;
00083 std::vector<float> feature_min_;
00084 float feature_lower_;
00085 float feature_upper_;
00086 };
00087
00088 #endif