head_based_subcluster.h
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) 2013-, Open Perception, Inc.
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 the copyright holder(s) 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  * head_based_subcluster.h
00037  * Created on: Nov 30, 2012
00038  * Author: Matteo Munaro
00039  */
00040 
00041 #ifndef PCL_PEOPLE_HEAD_BASED_SUBCLUSTER_H_
00042 #define PCL_PEOPLE_HEAD_BASED_SUBCLUSTER_H_
00043 
00044 #include <pcl/people/person_cluster.h>
00045 #include <pcl/people/height_map_2d.h>
00046 #include <pcl/point_types.h>
00047 
00048 namespace pcl
00049 {
00050   namespace people
00051   {
00056     template <typename PointT> class HeadBasedSubclustering;
00057 
00058     template <typename PointT>
00059     class HeadBasedSubclustering
00060     {
00061     public:
00062 
00063       typedef pcl::PointCloud<PointT> PointCloud;
00064       typedef boost::shared_ptr<PointCloud> PointCloudPtr;
00065       typedef boost::shared_ptr<const PointCloud> PointCloudConstPtr;
00066 
00068       HeadBasedSubclustering ();
00069 
00071       virtual ~HeadBasedSubclustering ();
00072 
00078       void
00079       subcluster (std::vector<pcl::people::PersonCluster<PointT> >& clusters);
00080 
00087       void
00088       mergeClustersCloseInFloorCoordinates (std::vector<pcl::people::PersonCluster<PointT> >& input_clusters,
00089           std::vector<pcl::people::PersonCluster<PointT> >& output_clusters);
00090 
00099       void
00100       createSubClusters (pcl::people::PersonCluster<PointT>& cluster, int maxima_number_after_filtering,  std::vector<int>& maxima_cloud_indices_filtered,
00101           std::vector<pcl::people::PersonCluster<PointT> >& subclusters);
00102 
00108       void
00109       setInputCloud (PointCloudPtr& cloud);
00110 
00116       void
00117       setGround (Eigen::VectorXf& ground_coeffs);
00118 
00124       void
00125       setSensorPortraitOrientation (bool vertical);
00126 
00132       void
00133       setHeadCentroid (bool head_centroid);
00134 
00140       void
00141       setInitialClusters (std::vector<pcl::PointIndices>& cluster_indices);
00142 
00149       void
00150       setHeightLimits (float min_height, float max_height);
00151 
00158       void
00159       setDimensionLimits (int min_points, int max_points);
00160 
00166       void
00167       setMinimumDistanceBetweenHeads (float heads_minimum_distance);
00168 
00175       void
00176       getHeightLimits (float& min_height, float& max_height);
00177 
00184       void
00185       getDimensionLimits (int& min_points, int& max_points);
00186 
00190       float
00191       getMinimumDistanceBetweenHeads ();
00192 
00193     protected:
00195       Eigen::VectorXf ground_coeffs_;            
00196       
00198       float sqrt_ground_coeffs_;              
00199       
00201       std::vector<pcl::PointIndices> cluster_indices_;   
00202       
00204       PointCloudPtr cloud_;                
00205       
00207       float max_height_;                  
00208       
00210       float min_height_;                  
00211       
00213       bool vertical_;                   
00214       
00217       bool head_centroid_;                                            
00218       
00220       int max_points_;                  
00221       
00223       int min_points_;                  
00224       
00226       float heads_minimum_distance_;           
00227     };
00228   } /* namespace people */
00229 } /* namespace pcl */
00230 #include <pcl/people/impl/head_based_subcluster.hpp>
00231 #endif /* PCL_PEOPLE_HEAD_BASED_SUBCLUSTER_H_ */


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:24:43