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 <pcl_conversions/pcl_conversions.h>
00037
00038 #include "jsk_pcl_ros/color_based_region_growing_segmentation.h"
00039
00040 #include "jsk_recognition_utils/pcl_conversion_util.h"
00041 #include "jsk_recognition_msgs/ClusterPointIndices.h"
00042
00043
00044 namespace jsk_pcl_ros
00045 {
00046
00047 void ColorBasedRegionGrowingSegmentation::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 (&ColorBasedRegionGrowingSegmentation::configCallback, this, _1, _2);
00053 srv_->setCallback (f);
00054 pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output", 1);
00055 onInitPostProcess();
00056 }
00057
00058 void ColorBasedRegionGrowingSegmentation::subscribe()
00059 {
00060 sub_ = pnh_->subscribe("input", 1, &ColorBasedRegionGrowingSegmentation::segment, this);
00061 }
00062
00063 void ColorBasedRegionGrowingSegmentation::unsubscribe()
00064 {
00065 sub_.shutdown();
00066 }
00067
00068 void ColorBasedRegionGrowingSegmentation::configCallback(Config &config, uint32_t level)
00069 {
00070 boost::mutex::scoped_lock lock(mutex_);
00071
00072 if (distance_threshold_ != config.distance_threshold) {
00073 distance_threshold_ = config.distance_threshold;
00074 }
00075 if (point_color_threshold_ != config.point_color_threshold) {
00076 point_color_threshold_ = config.point_color_threshold;
00077 }
00078 if (region_color_threshold_ != config.region_color_threshold) {
00079 region_color_threshold_ = config.region_color_threshold;
00080 }
00081 if (min_cluster_size_ != config.min_cluster_size) {
00082 min_cluster_size_ = config.min_cluster_size;
00083 }
00084 }
00085
00086 void ColorBasedRegionGrowingSegmentation::segment(const sensor_msgs::PointCloud2::ConstPtr& msg)
00087 {
00088 boost::mutex::scoped_lock lock(mutex_);
00089 pcl::search::Search <pcl::PointXYZRGB>::Ptr tree =
00090 pcl::search::Search <pcl::PointXYZRGB>::Ptr (new pcl::search::KdTree<pcl::PointXYZRGB>);
00091 pcl::PointCloud <pcl::PointXYZRGB>::Ptr cloud (new pcl::PointCloud <pcl::PointXYZRGB>);
00092 pcl::fromROSMsg(*msg, *cloud);
00093
00094 std::vector<int> indices;
00095 pcl::removeNaNFromPointCloud(*cloud, *cloud, indices);
00096
00097 pcl::RegionGrowingRGB<pcl::PointXYZRGB> reg;
00098 reg.setInputCloud (cloud);
00099 reg.setSearchMethod (tree);
00100 reg.setDistanceThreshold (distance_threshold_);
00101 reg.setPointColorThreshold (point_color_threshold_);
00102 reg.setRegionColorThreshold (region_color_threshold_);
00103 reg.setMinClusterSize (min_cluster_size_);
00104
00105 std::vector <pcl::PointIndices> clusters;
00106 reg.extract (clusters);
00107
00108 jsk_recognition_msgs::ClusterPointIndices output;
00109 output.header = msg->header;
00110
00111 for (size_t i = 0; i < clusters.size(); i++) {
00112 PCLIndicesMsg indices;
00113 indices.header = msg->header;
00114 indices.indices = clusters[i].indices;
00115 output.cluster_indices.push_back(indices);
00116 }
00117 pub_.publish(output);
00118 }
00119 }
00120
00121 #include <pluginlib/class_list_macros.h>
00122 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::ColorBasedRegionGrowingSegmentation, nodelet::Nodelet);