person_cluster.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  * person_cluster.h
00037  * Created on: Nov 30, 2012
00038  * Author: Matteo Munaro
00039  */
00040 
00041 #ifndef PCL_PEOPLE_PERSON_CLUSTER_H_
00042 #define PCL_PEOPLE_PERSON_CLUSTER_H_
00043 
00044 #include <pcl/point_types.h>
00045 #include <pcl/visualization/pcl_visualizer.h>
00046 
00047 namespace pcl
00048 {
00049   namespace people
00050   {
00055     template <typename PointT> class PersonCluster;
00056     template <typename PointT> bool operator<(const PersonCluster<PointT>& c1, const PersonCluster<PointT>& c2);
00057 
00058     template <typename PointT>
00059     class PersonCluster
00060     {
00061     protected:
00062 
00063       bool head_centroid_;
00064 
00066       float min_x_;
00068       float min_y_;
00070       float min_z_;
00071 
00073       float max_x_;
00075       float max_y_;
00077       float max_z_;
00078 
00080       float sum_x_;
00082       float sum_y_;
00084       float sum_z_;
00085 
00087       int n_;
00088 
00090       float c_x_;
00092       float c_y_;
00094       float c_z_;
00095 
00097       float height_;
00098 
00100       float distance_;
00102       float angle_;
00103 
00105       float angle_max_;
00107       float angle_min_;
00108       
00110       Eigen::Vector3f top_;
00112       Eigen::Vector3f bottom_;
00114       Eigen::Vector3f center_;
00115       
00117       Eigen::Vector3f ttop_;
00119       Eigen::Vector3f tbottom_;
00121       Eigen::Vector3f tcenter_;
00122 
00124       Eigen::Vector3f min_;
00126       Eigen::Vector3f max_;
00127 
00129       pcl::PointIndices points_indices_;
00130 
00132       bool vertical_;
00134       float person_confidence_;
00135 
00136     public:
00137 
00138       typedef pcl::PointCloud<PointT> PointCloud;
00139       typedef boost::shared_ptr<PointCloud> PointCloudPtr;
00140       typedef boost::shared_ptr<const PointCloud> PointCloudConstPtr;
00141 
00143       PersonCluster (
00144           const PointCloudPtr& input_cloud,
00145           const pcl::PointIndices& indices,
00146           const Eigen::VectorXf& ground_coeffs,
00147           float sqrt_ground_coeffs,
00148           bool head_centroid,
00149           bool vertical = false);
00150 
00152       virtual ~PersonCluster ();
00153 
00158       float
00159       getHeight ();
00160 
00166       float
00167       updateHeight (const Eigen::VectorXf& ground_coeffs);
00168 
00176       float
00177       updateHeight (const Eigen::VectorXf& ground_coeffs, float sqrt_ground_coeffs);
00178 
00184       float
00185       getDistance ();
00186 
00191       float
00192       getAngle ();
00193 
00198       float
00199       getAngleMin ();
00200 
00205       float
00206       getAngleMax ();
00207 
00212       pcl::PointIndices&
00213       getIndices ();
00214 
00219       Eigen::Vector3f&
00220       getTTop ();
00221 
00226       Eigen::Vector3f&
00227       getTBottom ();
00228 
00233       Eigen::Vector3f&
00234       getTCenter ();
00235 
00240       Eigen::Vector3f&
00241       getTop ();
00242 
00247       Eigen::Vector3f&
00248       getBottom ();
00249 
00254       Eigen::Vector3f&
00255       getCenter ();  
00256 
00257       //Eigen::Vector3f& getTMax();
00258 
00263       Eigen::Vector3f&
00264       getMin ();
00265 
00270       Eigen::Vector3f&
00271       getMax ();
00272 
00277       float
00278       getPersonConfidence ();
00279 
00284       int
00285       getNumberPoints ();
00286 
00291       void
00292       setHeight (float height);
00293 
00298       void
00299       setPersonConfidence (float confidence);
00300 
00306       void
00307       drawTBoundingBox (pcl::visualization::PCLVisualizer& viewer, int person_number);
00308 
00312       friend bool operator< <>(const PersonCluster<PointT>& c1, const PersonCluster<PointT>& c2);
00313 
00314     protected:
00315 
00319       void init(
00320           const PointCloudPtr& input_cloud,
00321           const pcl::PointIndices& indices,
00322           const Eigen::VectorXf& ground_coeffs,
00323           float sqrt_ground_coeffs,
00324           bool head_centroid,
00325           bool vertical);
00326 
00327     };
00328   } /* namespace people */
00329 } /* namespace pcl */
00330 #include <pcl/people/impl/person_cluster.hpp>
00331 #endif /* PCL_PEOPLE_PERSON_CLUSTER_H_ */


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:28:14