segment_cluster_creator.hpp
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 
00041 #include <jsk_recognition_msgs/BoundingBoxArray.h>
00042 
00043 using namespace pcl;
00044 
00045 class EuclideanCluster {
00046 public:
00047   EuclideanCluster(ros::NodeHandle nh, ros::NodeHandle n);
00048   void EuclideanCallback(const sensor_msgs::PointCloud2::ConstPtr &source_pc);
00049   void CropBox(pcl::PointCloud<pcl::PointXYZI>::Ptr cloud, pcl::PointXYZ min, pcl::PointXYZ max);
00050   void Clustering(pcl::PointCloud<pcl::PointXYZI>::Ptr cloud);
00051  
00052   void run();
00053 
00054 private:
00055   ros::NodeHandle nh_;
00056   ros::Rate rate_;
00057   std::string frame_id_;
00058   ros::Publisher fileterd_cloud_pub_;
00059   ros::Publisher euclidean_cluster_pub_;
00060   ros::Subscriber source_pc_sub_;
00061   tf::TransformListener tf_;
00062   tf::TransformBroadcaster br_;
00063 
00064   // Threshold
00065   double clusterTolerance_;
00066   int minSize_;
00067   int maxSize_;
00068   int accumulation_counter_;
00069   pcl::PointXYZ crop_min_, crop_max_;
00070 
00071   // output file name
00072   std::string output_file_prefix_;
00073 };
00074 
00075 #endif /* EUCLIDEAN_CLUSTER_H */


target_obejct_detector
Author(s): CIR-KIT
autogenerated on Thu Jun 6 2019 20:19:57