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::updateDiagnostic(
00067 diagnostic_updater::DiagnosticStatusWrapper &stat)
00068 {
00069 if (vital_checker_->isAlive()) {
00070 stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00071 "SupervoxelSegmentation running");
00072 }
00073 else {
00074 jsk_topic_tools::addDiagnosticErrorSummary(
00075 "SupervoxelSegmentation", vital_checker_, stat);
00076 }
00077 }
00078
00079 void SupervoxelSegmentation::segment(
00080 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
00081 {
00082 boost::mutex::scoped_lock lock(mutex_);
00083 vital_checker_->poke();
00084 if (cloud_msg->data.size() > 0) {
00085 pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
00086 pcl::fromROSMsg(*cloud_msg, *cloud);
00087 pcl::SupervoxelClustering<PointT> super(voxel_resolution_,
00088 seed_resolution_,
00089 use_transform_);
00090 super.setInputCloud(cloud);
00091 super.setColorImportance(color_importance_);
00092 super.setSpatialImportance(spatial_importance_);
00093 super.setNormalImportance(normal_importance_);
00094 std::map<uint32_t, pcl::Supervoxel<PointT>::Ptr > supervoxel_clusters;
00095 super.extract(supervoxel_clusters);
00096 pcl::PointCloud<PointT>::Ptr output (new pcl::PointCloud<PointT>);
00097 std::vector<pcl::PointIndices> all_indices;
00098 for (std::map<uint32_t, pcl::Supervoxel<PointT>::Ptr >::iterator
00099 it = supervoxel_clusters.begin();
00100 it != supervoxel_clusters.end();
00101 ++it) {
00102 pcl::Supervoxel<PointT>::Ptr super_voxel = it->second;
00103 pcl::PointCloud<PointT>::Ptr super_voxel_cloud = super_voxel->voxels_;
00104 pcl::PointIndices indices;
00105
00106 for (size_t i = 0; i < super_voxel_cloud->size(); i++) {
00107 indices.indices.push_back(i + output->points.size());
00108 }
00109 all_indices.push_back(indices);
00110 *output = *output + *super_voxel_cloud;
00111 }
00112 sensor_msgs::PointCloud2 ros_cloud;
00113 pcl::toROSMsg(*output, ros_cloud);
00114 ros_cloud.header = cloud_msg->header;
00115 jsk_recognition_msgs::ClusterPointIndices ros_indices;
00116 ros_indices.cluster_indices = pcl_conversions::convertToROSPointIndices(
00117 all_indices,
00118 cloud_msg->header);
00119 ros_indices.header = cloud_msg->header;
00120 pub_cloud_.publish(ros_cloud);
00121 pub_indices_.publish(ros_indices);
00122 }
00123 }
00124
00125 void SupervoxelSegmentation::configCallback (Config &config, uint32_t level)
00126 {
00127 boost::mutex::scoped_lock lock(mutex_);
00128 color_importance_ = config.color_importance;
00129 spatial_importance_ = config.spatial_importance;
00130 normal_importance_ = config.normal_importance;
00131 voxel_resolution_ = config.voxel_resolution;
00132 seed_resolution_ = config.seed_resolution;
00133 use_transform_ = config.use_transform;
00134 }
00135 }
00136
00137
00138 #include <pluginlib/class_list_macros.h>
00139 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::SupervoxelSegmentation, nodelet::Nodelet);