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