supervoxels.hpp
Go to the documentation of this file.
00001 /*
00002 * Software License Agreement  (BSD License)
00003 *
00004 *  Point Cloud Library  (PCL) - www.pointclouds.org
00005 *  Copyright  (c) 2012, Jeremie Papon.
00006 *
00007 *  All rights reserved.
00008 *
00009 *  Redistribution and use in source and binary forms, with or without
00010 *  modification, are permitted provided that the following conditions
00011 *  are met:
00012 *
00013 *   * Redistributions of source code must retain the above copyright
00014 *     notice, this list of conditions and the following disclaimer.
00015 *   * Redistributions in binary form must reproduce the above
00016 *     copyright notice, this list of conditions and the following
00017 *     disclaimer in the documentation and/or other materials provided
00018 *     with the distribution.
00019 *   * Neither the name of Willow Garage, Inc. nor the names of its
00020 *     contributors may be used to endorse or promote products derived
00021 *     from this software without specific prior written permission.
00022 *
00023 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES  (INCLUDING,
00029 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032 *  LIABILITY, OR TORT  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034 *  POSSIBILITY OF SUCH DAMAGE.
00035 *
00036 */
00037 
00038 #ifndef IMPL_SUPERVOXELS_HPP_
00039 #define IMPL_SUPERVOXELS_HPP_
00040 
00041 #include <pcl/apps/cloud_composer/tools/supervoxels.h>
00042 #include <pcl/apps/cloud_composer/impl/cloud_item.hpp>
00043 #include <pcl/apps/cloud_composer/items/normals_item.h>
00044 #include <pcl/point_cloud.h>
00045 #include <pcl/segmentation/supervoxel_clustering.h>
00046 
00047 
00048 template <typename PointT> QList <pcl::cloud_composer::CloudComposerItem*>
00049 pcl::cloud_composer::SupervoxelsTool::performTemplatedAction (QList <const CloudComposerItem*> input_data)
00050 {
00051   QList <CloudComposerItem*> output;  
00052   
00053   foreach (const CloudComposerItem* input_item, input_data)
00054   {
00055    // if ( !input_item->isSanitized () )
00056   //  {
00057   //    qCritical () << "SupervoxelsTool requires sanitized input!";
00058   //    return output;
00059   //  }
00060     QVariant variant = input_item->data (ItemDataRole::CLOUD_TEMPLATED);
00061     if ( ! variant.canConvert <typename PointCloud<PointT>::Ptr> () )
00062     {  
00063       qWarning () << "Attempted to cast to template type which does not exist in this item! (input list)";
00064       return output;
00065     }
00066     typename PointCloud <PointT>::Ptr input_cloud = variant.value <typename PointCloud<PointT>::Ptr> ();
00067     //TODO: Check if Voxelized
00068     
00069 }
00070   
00071 
00072   foreach (const CloudComposerItem* input_item, input_data)
00073   {  
00074     QVariant variant = input_item->data (ItemDataRole::CLOUD_TEMPLATED);
00075     typename PointCloud <PointT>::Ptr input_cloud = variant.value <typename PointCloud<PointT>::Ptr> ();
00076     
00077     float resolution = parameter_model_->getProperty("Resolution").toFloat ();
00078     qDebug () << "Octree resolution = "<<resolution;
00079     float seed_resolution = parameter_model_->getProperty("Seed Resolution").toFloat ();
00080     qDebug () << "Seed resolution = "<<seed_resolution;
00081     
00082     float rgb_weight = parameter_model_->getProperty("RGB Weight").toFloat ();
00083     float normal_weight = parameter_model_->getProperty("Normals Weight").toFloat ();
00084     float spatial_weight = parameter_model_->getProperty("Spatial Weight").toFloat ();
00085     
00086   
00087     pcl::SupervoxelClustering<PointT> super (resolution, seed_resolution);
00088     super.setInputCloud (input_cloud);
00089     super.setColorImportance (rgb_weight);
00090     super.setSpatialImportance (spatial_weight);
00091     super.setNormalImportance (normal_weight);
00092     std::map <uint32_t, typename pcl::Supervoxel<PointT>::Ptr > supervoxel_clusters;
00093     super.extract (supervoxel_clusters);
00094     
00095     std::map <uint32_t, typename pcl::Supervoxel<PointT>::Ptr > refined_supervoxel_clusters;
00096     super.refineSupervoxels (3, refined_supervoxel_clusters);
00097   
00098     typename pcl::PointCloud<PointXYZRGBA>::Ptr color_segments;
00099     color_segments= super.getColoredVoxelCloud ();
00100     
00101     CloudItem*  cloud_item_out = CloudItem::createCloudItemFromTemplate<PointXYZRGBA>(input_item->text(),color_segments);
00102  
00103     
00104     output.append (cloud_item_out);
00105     
00106   }
00107   
00108   
00109   
00110   
00111   return output;
00112   
00113 }
00114 
00115 
00116 
00117 
00118 #define PCL_INSTANTIATE_performTemplatedAction(T) template PCL_EXPORTS void pcl::cloud_composer::SupervoxelsTool::performTemplatedAction<T> (QList <const CloudComposerItem*>);
00119 
00120 
00121 
00122 #endif //IMPL_SUPERVOXELS_HPP_


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:34:09