Go to the documentation of this file.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
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef _CONVEX_CONNECTED_VOXELS_H_
00038 #define _CONVEX_CONNECTED_VOXELS_H_
00039
00040 #include <jsk_pcl_ros/region_adjacency_graph.h>
00041 #include <jsk_recognition_msgs/ClusterPointIndices.h>
00042 #include <jsk_pcl_ros/pcl_conversion_util.h>
00043 #include <jsk_topic_tools/diagnostic_nodelet.h>
00044
00045
00046 #include <ros/ros.h>
00047 #include <ros/console.h>
00048
00049
00050 #include <image_transport/image_transport.h>
00051 #include <cv_bridge/cv_bridge.h>
00052 #include <sensor_msgs/image_encodings.h>
00053 #include <sensor_msgs/PointCloud2.h>
00054 #include <pcl_conversions/pcl_conversions.h>
00055
00056
00057 #include <opencv2/imgproc/imgproc.hpp>
00058 #include <opencv2/highgui/highgui.hpp>
00059
00060
00061 #include <pcl/point_cloud.h>
00062 #include <pcl/point_types.h>
00063 #include <pcl/kdtree/kdtree_flann.h>
00064 #include <pcl/kdtree/kdtree.h>
00065 #include <pcl/filters/passthrough.h>
00066 #include <pcl/features/normal_3d_omp.h>
00067 #include <pcl/sample_consensus/method_types.h>
00068 #include <pcl/sample_consensus/model_types.h>
00069 #include <pcl/segmentation/sac_segmentation.h>
00070 #include <pcl/segmentation/extract_clusters.h>
00071 #include <pcl/filters/extract_indices.h>
00072 #include <pcl/common/centroid.h>
00073 #include <pcl/common/impl/common.hpp>
00074 #include <pcl/registration/distances.h>
00075
00076 #include <map>
00077 #include <string>
00078
00079
00080 namespace jsk_pcl_ros
00081 {
00082 class ConvexConnectedVoxels: public jsk_topic_tools::DiagnosticNodelet
00083 {
00084 public:
00085 ConvexConnectedVoxels() : DiagnosticNodelet("ConvexConnectedVoxels") {}
00086 typedef pcl::PointXYZRGB PointT;
00087
00088 protected:
00089 void cloud_cb(
00090 const sensor_msgs::PointCloud2::ConstPtr &);
00091 void indices_cb(
00092 const jsk_recognition_msgs::ClusterPointIndices &);
00093 void segmentCloud(
00094 const pcl::PointCloud<PointT>::Ptr,
00095 const std::vector<pcl::PointIndices> &,
00096 std::vector<pcl::PointCloud<PointT>::Ptr> &,
00097 std::vector<pcl::PointCloud<pcl::Normal>::Ptr> &,
00098 pcl::PointCloud<pcl::PointXYZ>::Ptr);
00099 void estimatePointCloudNormals(
00100 const pcl::PointCloud<PointT>::Ptr,
00101 pcl::PointCloud<pcl::Normal>::Ptr,
00102 const int = 8, const double = 0.02,
00103 bool = true);
00104 void nearestNeigborSearch(
00105 pcl::PointCloud<pcl::PointXYZ>::Ptr,
00106 std::vector<std::vector<int> > &,
00107 const int = 8,
00108 const double = 0.02,
00109 bool = true);
00110 void getConvexLabelCloudIndices(
00111 const std::vector<pcl::PointCloud<PointT>::Ptr> &,
00112 pcl::PointCloud<PointT>::Ptr,
00113 const std::vector<int> &,
00114 std::map<int, pcl::PointIndices> &);
00115
00116 boost::mutex mutex_;
00117 ros::Subscriber sub_cloud_;
00118 ros::Subscriber sub_indices_;
00119 ros::Publisher pub_indices_;
00120 ros::NodeHandle nh_;
00121
00122 virtual void onInit();
00123 virtual void subscribe();
00124 virtual void unsubscribe();
00125 virtual void updateDiagnostic(
00126 diagnostic_updater::DiagnosticStatusWrapper &);
00127
00128 private:
00129 std::vector<pcl::PointIndices> indices_;
00130 };
00131 }
00132
00133 #endif // _CONVEX_CONNECTED_VOXELS_H_