person_classifier.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_classifier.h
00037  * Created on: Nov 30, 2012
00038  * Author: Matteo Munaro
00039  */
00040  
00041 #ifndef PCL_PEOPLE_PERSON_CLASSIFIER_H_
00042 #define PCL_PEOPLE_PERSON_CLASSIFIER_H_
00043 
00044 #include <pcl/people/person_cluster.h>
00045 #include <pcl/people/hog.h>
00046 
00047 namespace pcl
00048 {
00049   namespace people
00050   {
00051     template <typename PointT> class PersonClassifier;
00052 
00053     template <typename PointT>
00054     class PersonClassifier
00055     {
00056     protected:
00057 
00059       int window_height_;          
00060       
00062       int window_width_;          
00063       
00065       float SVM_offset_;          
00066       
00068       std::vector<float> SVM_weights_;  
00069 
00070     public:
00071 
00072       typedef pcl::PointCloud<PointT> PointCloud;
00073       typedef boost::shared_ptr<PointCloud> PointCloudPtr;
00074 
00076       PersonClassifier ();
00077 
00079       virtual ~PersonClassifier ();
00080 
00087       bool
00088       loadSVMFromFile (std::string svm_filename);
00089 
00098       void
00099       setSVM (int window_height, int window_width, std::vector<float> SVM_weights, float SVM_offset);
00100 
00109       void
00110       getSVM (int& window_height, int& window_width, std::vector<float>& SVM_weights, float& SVM_offset);
00111 
00120       void
00121       resize (PointCloudPtr& input_image, PointCloudPtr& output_image,
00122               int width, int height);
00123 
00134       void
00135       copyMakeBorder (PointCloudPtr& input_image, PointCloudPtr& output_image,
00136           int xmin, int ymin, int width, int height);
00137 
00147       double
00148       evaluate (float height, float xc, float yc, PointCloudPtr& image);
00149 
00160       double
00161       evaluate (PointCloudPtr& image, Eigen::Vector3f& bottom, Eigen::Vector3f& top, Eigen::Vector3f& centroid,
00162          bool vertical);
00163     };
00164   } /* namespace people */
00165 } /* namespace pcl */
00166 #include <pcl/people/impl/person_classifier.hpp>
00167 #endif /* PCL_PEOPLE_PERSON_CLASSIFIER_H_ */


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