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 #define BOOST_PARAMETER_MAX_ARITY 7
00037 #include "jsk_pcl_ros/supervoxel_segmentation.h"
00038 #include <pcl/segmentation/supervoxel_clustering.h>
00039 namespace jsk_pcl_ros
00040 {
00041   void SupervoxelSegmentation::onInit()
00042   {
00043     DiagnosticNodelet::onInit();
00044     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00045     dynamic_reconfigure::Server<Config>::CallbackType f =
00046       boost::bind (
00047         &SupervoxelSegmentation::configCallback, this, _1, _2);
00048     srv_->setCallback (f);
00049     pub_indices_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(
00050       *pnh_, "output/indices", 1);
00051     pub_cloud_ = advertise<sensor_msgs::PointCloud2>(
00052       *pnh_, "output/cloud", 1);
00053     onInitPostProcess();
00054   }
00055 
00056   void SupervoxelSegmentation::subscribe()
00057   {
00058     sub_ = pnh_->subscribe("input", 1, &SupervoxelSegmentation::segment, this);
00059   }
00060 
00061   void SupervoxelSegmentation::unsubscribe()
00062   {
00063     sub_.shutdown();
00064   }
00065 
00066   void SupervoxelSegmentation::segment(
00067     const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
00068   {
00069     boost::mutex::scoped_lock lock(mutex_);
00070     vital_checker_->poke();
00071     if (cloud_msg->data.size() > 0) {
00072       pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
00073       pcl::fromROSMsg(*cloud_msg, *cloud);
00074       pcl::SupervoxelClustering<PointT> super(voxel_resolution_,
00075                                               seed_resolution_,
00076                                               use_transform_);
00077       super.setInputCloud(cloud);
00078       super.setColorImportance(color_importance_);
00079       super.setSpatialImportance(spatial_importance_);
00080       super.setNormalImportance(normal_importance_);
00081       std::map<uint32_t, pcl::Supervoxel<PointT>::Ptr > supervoxel_clusters;
00082       super.extract(supervoxel_clusters);
00083       pcl::PointCloud<PointT>::Ptr output (new pcl::PointCloud<PointT>);
00084       std::vector<pcl::PointIndices> all_indices;
00085       for (std::map<uint32_t, pcl::Supervoxel<PointT>::Ptr >::iterator
00086              it = supervoxel_clusters.begin();
00087            it != supervoxel_clusters.end();
00088            ++it) {
00089         pcl::Supervoxel<PointT>::Ptr super_voxel = it->second;
00090         pcl::PointCloud<PointT>::Ptr super_voxel_cloud = super_voxel->voxels_;
00091         pcl::PointIndices indices;
00092         
00093         for (size_t i = 0; i < super_voxel_cloud->size(); i++) {
00094           indices.indices.push_back(i + output->points.size());
00095         }
00096         all_indices.push_back(indices);
00097         *output = *output + *super_voxel_cloud; 
00098       }
00099       sensor_msgs::PointCloud2 ros_cloud;
00100       pcl::toROSMsg(*output, ros_cloud);
00101       ros_cloud.header = cloud_msg->header;
00102       jsk_recognition_msgs::ClusterPointIndices ros_indices;
00103       ros_indices.cluster_indices = pcl_conversions::convertToROSPointIndices(
00104         all_indices,
00105         cloud_msg->header);
00106       ros_indices.header = cloud_msg->header;
00107       pub_cloud_.publish(ros_cloud);
00108       pub_indices_.publish(ros_indices);
00109     }
00110   }
00111 
00112   void SupervoxelSegmentation::configCallback (Config &config, uint32_t level)
00113   {
00114     boost::mutex::scoped_lock lock(mutex_);
00115     color_importance_ = config.color_importance;
00116     spatial_importance_ = config.spatial_importance;
00117     normal_importance_ = config.normal_importance;
00118     voxel_resolution_ = config.voxel_resolution;
00119     seed_resolution_ = config.seed_resolution;
00120     use_transform_ = config.use_transform;
00121   }
00122 }
00123 
00124 
00125 #include <pluginlib/class_list_macros.h>
00126 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::SupervoxelSegmentation, nodelet::Nodelet);