sgf2.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) 2010-2011, Willow Garage, 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 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 PCL_FEATURES_SGF2_H_
00039 #define PCL_FEATURES_SGF2_H_
00040 
00041 #include <pcl17/features/feature.h>
00042 #include <pcl17/features/normal_3d.h>
00043 #include <numeric>
00044 
00045 namespace pcl17 {
00046 const int SGF2_SIZE = 1;
00047 
00048 template<typename PointInT, typename PointOutT>
00049 class SGF2Estimation: public Feature<PointInT, PointOutT> {
00050 
00051 public:
00052 
00053         using Feature<PointInT, PointOutT>::feature_name_;
00054         using Feature<PointInT, PointOutT>::input_;
00055         using Feature<PointInT, PointOutT>::indices_;
00056         using Feature<PointInT, PointOutT>::search_parameter_;
00057         using Feature<PointInT, PointOutT>::k_;
00058 
00059         typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00060         typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00061 
00063         SGF2Estimation() {
00064                 feature_name_ = "SGF2Estimation";
00065                 k_ = 1;
00066         }
00067         ;
00068 
00070         void computeFeature(PointCloudOut &output) {
00071 
00072                 PointCloud<Normal>::Ptr normals(new PointCloud<Normal> ());
00073                 NormalEstimation<PointInT, Normal> n;
00074 
00075                 std::vector<int> nn_indices;
00076                 std::vector<float> nn_sqr_dists;
00077                 Eigen::Vector4f parameters;
00078                 Eigen::VectorXf vec(indices_->size());
00079 
00080                 for (size_t idx = 0; idx < indices_->size(); ++idx) {
00081                         float curvature;
00082                         this->searchForNeighbors((*indices_)[idx], search_parameter_,
00083                                         nn_indices, nn_sqr_dists);
00084                         n.computePointNormal(*input_, nn_indices, parameters, curvature);
00085                         vec[idx] = curvature;
00086                 }
00087 
00088                 output.points[0].histogram[0] = vec.mean();
00089 
00090         }
00092 
00093 
00094 private:
00095 
00099         void computeFeatureEigen(pcl17::PointCloud<Eigen::MatrixXf> &) {
00100         }
00101 };
00102 }
00103 
00104 #endif  //#ifndef PCL_FEATURES_SGF2_H_
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


furniture_features
Author(s): Stefan
autogenerated on Sun Oct 6 2013 11:58:55