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 #include "jsk_pcl_ros/region_growing_segmentation.h"
00037
00038 #include "jsk_recognition_msgs/ClusterPointIndices.h"
00039 #include <pcl/segmentation/impl/region_growing.hpp>
00040 #include <pluginlib/class_list_macros.h>
00041
00042 #include "jsk_recognition_utils/pcl_conversion_util.h"
00043
00044 namespace jsk_pcl_ros
00045 {
00046
00047 void RegionGrowingSegmentation::onInit()
00048 {
00049 ConnectionBasedNodelet::onInit();
00050 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00051 dynamic_reconfigure::Server<Config>::CallbackType f =
00052 boost::bind (&RegionGrowingSegmentation::configCallback, this, _1, _2);
00053 srv_->setCallback (f);
00054 pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output", 1);
00055 onInitPostProcess();
00056 }
00057
00058 void RegionGrowingSegmentation::subscribe()
00059 {
00060 sub_ = pnh_->subscribe("input", 1, &RegionGrowingSegmentation::segment, this);
00061 }
00062
00063 void RegionGrowingSegmentation::unsubscribe()
00064 {
00065 sub_.shutdown();
00066 }
00067
00068 void RegionGrowingSegmentation::configCallback(Config &config, uint32_t level)
00069 {
00070 boost::mutex::scoped_lock lock(mutex_);
00071
00072 if (number_of_neighbors_ != config.number_of_neighbors) {
00073 number_of_neighbors_ = config.number_of_neighbors;
00074 }
00075 if (min_size_ != config.min_size) {
00076 min_size_ = config.min_size;
00077 }
00078 if (max_size_ != config.max_size) {
00079 max_size_ = config.max_size;
00080 }
00081 if (smoothness_threshold_ != config.smoothness_threshold) {
00082 smoothness_threshold_ = config.smoothness_threshold;
00083 }
00084 if (curvature_threshold_ != config.curvature_threshold) {
00085 curvature_threshold_ = config.curvature_threshold;
00086 }
00087 }
00088
00089 void RegionGrowingSegmentation::segment(const sensor_msgs::PointCloud2::ConstPtr& msg)
00090 {
00091 boost::mutex::scoped_lock lock(mutex_);
00092 pcl::search::Search<pcl::PointNormal>::Ptr tree = boost::shared_ptr<pcl::search::Search<pcl::PointNormal> > (new pcl::search::KdTree<pcl::PointNormal>);
00093 pcl::PointCloud<pcl::PointNormal> cloud;
00094 pcl::fromROSMsg(*msg, cloud);
00095
00096 pcl::RegionGrowing<pcl::PointNormal, pcl::PointNormal> reg;
00097 reg.setMinClusterSize (min_size_);
00098 reg.setMaxClusterSize (max_size_);
00099 reg.setSearchMethod (tree);
00100 reg.setNumberOfNeighbours (number_of_neighbors_);
00101 reg.setInputCloud (cloud.makeShared());
00102
00103 reg.setInputNormals (cloud.makeShared());
00104 reg.setSmoothnessThreshold (smoothness_threshold_);
00105 reg.setCurvatureThreshold (curvature_threshold_);
00106
00107 std::vector <pcl::PointIndices> clusters;
00108 reg.extract (clusters);
00109
00110 jsk_recognition_msgs::ClusterPointIndices output;
00111 output.header = msg->header;
00112
00113 for (size_t i = 0; i < clusters.size(); i++) {
00114 PCLIndicesMsg indices;
00115 indices.header = msg->header;
00116 indices.indices = clusters[i].indices;
00117 output.cluster_indices.push_back(indices);
00118 }
00119 pub_.publish(output);
00120 }
00121
00122 }
00123
00124 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::RegionGrowingSegmentation,
00125 nodelet::Nodelet);