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 #ifndef JSK_PCL_ROS_EUCLIDEAN_CLUSTER_EXTRACTION_NODELET_H_
00037 #define JSK_PCL_ROS_EUCLIDEAN_CLUSTER_EXTRACTION_NODELET_H_
00038
00039 #include <ros/ros.h>
00040 #include <ros/names.h>
00041
00042 #include <std_msgs/ColorRGBA.h>
00043
00044 #include <dynamic_reconfigure/server.h>
00045
00046 #include <pcl_ros/pcl_nodelet.h>
00047
00048 #include <pcl/point_types.h>
00049 #include <pcl/impl/point_types.hpp>
00050 #include <pcl/kdtree/kdtree_flann.h>
00051 #include <pcl/segmentation/sac_segmentation.h>
00052 #include <pcl/segmentation/extract_clusters.h>
00053 #include <pcl/filters/extract_indices.h>
00054 #include <pcl/common/centroid.h>
00055
00056 #include "jsk_recognition_msgs/ClusterPointIndices.h"
00057 #include "jsk_recognition_msgs/EuclideanSegment.h"
00058 #include "jsk_recognition_msgs/Int32Stamped.h"
00059
00060 #include "jsk_pcl_ros/EuclideanClusteringConfig.h"
00061 #include <Eigen/StdVector>
00062 #include "jsk_recognition_utils/pcl_util.h"
00063 #include "jsk_recognition_utils/pcl_conversion_util.h"
00064 #include <jsk_topic_tools/time_accumulator.h>
00065
00066 #include <jsk_topic_tools/diagnostic_nodelet.h>
00067
00068 namespace jsk_pcl_ros
00069 {
00070 class EuclideanClustering : public jsk_topic_tools::DiagnosticNodelet
00071 {
00072 public:
00073 typedef jsk_pcl_ros::EuclideanClusteringConfig Config;
00074 typedef std::vector<Eigen::Vector4f,
00075 Eigen::aligned_allocator<Eigen::Vector4f> >
00076 Vector4fVector;
00077 EuclideanClustering() : DiagnosticNodelet("EuclideanClustering") {}
00078 protected:
00079 boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00080 boost::mutex mutex_;
00081
00082 void configCallback (Config &config, uint32_t level);
00083 ros::Publisher result_pub_;
00084 ros::Subscriber sub_input_;
00085 ros::Publisher cluster_num_pub_;
00086
00087 ros::ServiceServer service_;
00088
00089 double tolerance;
00090 double label_tracking_tolerance;
00091 int minsize_;
00092 int maxsize_;
00093
00094 jsk_topic_tools::TimeAccumulator segmentation_acc_;
00095 jsk_topic_tools::TimeAccumulator kdtree_acc_;
00096 jsk_recognition_utils::Counter cluster_counter_;
00097
00098
00099 Vector4fVector cogs_;
00100
00101 virtual void onInit();
00102 virtual void extract(const sensor_msgs::PointCloud2ConstPtr &input);
00103 bool serviceCallback(jsk_recognition_msgs::EuclideanSegment::Request &req,
00104 jsk_recognition_msgs::EuclideanSegment::Response &res);
00105 virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat);
00106 virtual std::vector<pcl::PointIndices> pivotClusterIndices(
00107 std::vector<int>& pivot_table,
00108 std::vector<pcl::PointIndices>& cluster_indices);
00109
00110 virtual std::vector<int> buildLabelTrackingPivotTable(
00111 double* D,
00112 Vector4fVector cogs,
00113 Vector4fVector new_cogs,
00114 double label_tracking_tolerance);
00115
00116 virtual void computeDistanceMatrix(
00117 double* D,
00118 Vector4fVector& old_cogs,
00119 Vector4fVector& new_cogs);
00120
00121 virtual void
00122 computeCentroidsOfClusters(Vector4fVector& ret,
00123 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
00124 std::vector<pcl::PointIndices> cluster_indices);
00125
00126 virtual void subscribe();
00127 virtual void unsubscribe();
00128 };
00129
00130 }
00131
00132 #endif