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_pcl_ros/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 }
00056
00057 void RegionGrowingSegmentation::subscribe()
00058 {
00059 sub_ = pnh_->subscribe("input", 1, &RegionGrowingSegmentation::segment, this);
00060 }
00061
00062 void RegionGrowingSegmentation::unsubscribe()
00063 {
00064 sub_.shutdown();
00065 }
00066
00067 void RegionGrowingSegmentation::configCallback(Config &config, uint32_t level)
00068 {
00069 boost::mutex::scoped_lock lock(mutex_);
00070
00071 if (number_of_neighbors_ != config.number_of_neighbors) {
00072 number_of_neighbors_ = config.number_of_neighbors;
00073 }
00074 if (min_size_ != config.min_size) {
00075 min_size_ = config.min_size;
00076 }
00077 if (max_size_ != config.max_size) {
00078 max_size_ = config.max_size;
00079 }
00080 if (smoothness_threshold_ != config.smoothness_threshold) {
00081 smoothness_threshold_ = config.smoothness_threshold;
00082 }
00083 if (curvature_threshold_ != config.curvature_threshold) {
00084 curvature_threshold_ = config.curvature_threshold;
00085 }
00086 }
00087
00088 void RegionGrowingSegmentation::segment(const sensor_msgs::PointCloud2::ConstPtr& msg)
00089 {
00090 boost::mutex::scoped_lock lock(mutex_);
00091 pcl::search::Search<pcl::PointNormal>::Ptr tree = boost::shared_ptr<pcl::search::Search<pcl::PointNormal> > (new pcl::search::KdTree<pcl::PointNormal>);
00092 pcl::PointCloud<pcl::PointNormal> cloud;
00093 pcl::fromROSMsg(*msg, cloud);
00094
00095 pcl::RegionGrowing<pcl::PointNormal, pcl::PointNormal> reg;
00096 reg.setMinClusterSize (min_size_);
00097 reg.setMaxClusterSize (max_size_);
00098 reg.setSearchMethod (tree);
00099 reg.setNumberOfNeighbours (number_of_neighbors_);
00100 reg.setInputCloud (cloud.makeShared());
00101
00102 reg.setInputNormals (cloud.makeShared());
00103 reg.setSmoothnessThreshold (smoothness_threshold_);
00104 reg.setCurvatureThreshold (curvature_threshold_);
00105
00106 std::vector <pcl::PointIndices> clusters;
00107 reg.extract (clusters);
00108
00109 jsk_recognition_msgs::ClusterPointIndices output;
00110 output.header = msg->header;
00111
00112 for (size_t i = 0; i < clusters.size(); i++) {
00113 PCLIndicesMsg indices;
00114 indices.header = msg->header;
00115 indices.indices = clusters[i].indices;
00116 output.cluster_indices.push_back(indices);
00117 }
00118 pub_.publish(output);
00119 }
00120
00121 }
00122
00123 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::RegionGrowingSegmentation,
00124 nodelet::Nodelet);