ppf.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) 2011, Alexandru-Eugen Ichim
00006  *                      Willow Garage, Inc
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  * $Id: ppf.hpp 5036 2012-03-12 08:54:15Z rusu $
00037  */
00038 
00039 #ifndef PCL_FEATURES_IMPL_PPF_H_
00040 #define PCL_FEATURES_IMPL_PPF_H_
00041 
00042 #include <pcl/features/ppf.h>
00043 #include <pcl/features/pfh.h>
00044 
00046 template <typename PointInT, typename PointNT, typename PointOutT>
00047 pcl::PPFEstimation<PointInT, PointNT, PointOutT>::PPFEstimation ()
00048     : FeatureFromNormals <PointInT, PointNT, PointOutT> ()
00049 {
00050   feature_name_ = "PPFEstimation";
00051   // Slight hack in order to pass the check for the presence of a search method in Feature::initCompute ()
00052   Feature<PointInT, PointOutT>::tree_.reset (new pcl::search::KdTree <PointInT> ());
00053   Feature<PointInT, PointOutT>::search_radius_ = 1.0f;
00054 }
00055 
00056 
00058 template <typename PointInT, typename PointNT, typename PointOutT> void
00059 pcl::PPFEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut &output)
00060 {
00061   // Initialize output container - overwrite the sizes done by Feature::initCompute ()
00062   output.points.resize (indices_->size () * input_->points.size ());
00063   output.height = 1;
00064   output.width = static_cast<uint32_t> (output.points.size ());
00065   output.is_dense = true;
00066 
00067   // Compute point pair features for every pair of points in the cloud
00068   for (size_t index_i = 0; index_i < indices_->size (); ++index_i)
00069   {
00070     size_t i = (*indices_)[index_i];
00071     for (size_t j = 0 ; j < input_->points.size (); ++j)
00072     {
00073       PointOutT p;
00074       if (i != j)
00075       {
00076         if (//pcl::computePPFPairFeature
00077             pcl::computePairFeatures (input_->points[i].getVector4fMap (),
00078                                       normals_->points[i].getNormalVector4fMap (),
00079                                       input_->points[j].getVector4fMap (),
00080                                       normals_->points[j].getNormalVector4fMap (),
00081                                       p.f1, p.f2, p.f3, p.f4))
00082         {
00083           // Calculate alpha_m angle
00084           Eigen::Vector3f model_reference_point = input_->points[i].getVector3fMap (),
00085                           model_reference_normal = normals_->points[i].getNormalVector3fMap (),
00086                           model_point = input_->points[j].getVector3fMap ();
00087           Eigen::AngleAxisf rotation_mg (acosf (model_reference_normal.dot (Eigen::Vector3f::UnitX ())),
00088                                          model_reference_normal.cross (Eigen::Vector3f::UnitX ()).normalized ());
00089           Eigen::Affine3f transform_mg = Eigen::Translation3f ( rotation_mg * ((-1) * model_reference_point)) * rotation_mg;
00090 
00091           Eigen::Vector3f model_point_transformed = transform_mg * model_point;
00092           float angle = atan2f ( -model_point_transformed(2), model_point_transformed(1));
00093           if (sin (angle) * model_point_transformed(2) < 0.0f)
00094             angle *= (-1);
00095           p.alpha_m = -angle;
00096         }
00097         else
00098         {
00099           PCL_ERROR ("[pcl::%s::computeFeature] Computing pair feature vector between points %zu and %zu went wrong.\n", getClassName ().c_str (), i, j);
00100           p.f1 = p.f2 = p.f3 = p.f4 = p.alpha_m = std::numeric_limits<float>::quiet_NaN ();
00101           output.is_dense = false;
00102         }
00103       }
00104       // Do not calculate the feature for identity pairs (i, i) as they are not used
00105       // in the following computations
00106       else
00107       {
00108         p.f1 = p.f2 = p.f3 = p.f4 = p.alpha_m = std::numeric_limits<float>::quiet_NaN ();
00109         output.is_dense = false;
00110       }
00111 
00112       output.points[index_i*input_->points.size () + j] = p;
00113     }
00114   }
00115 }
00116 
00118 template <typename PointInT, typename PointNT> void
00119 pcl::PPFEstimation<PointInT, PointNT, Eigen::MatrixXf>::computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output)
00120 {
00121   // Initialize output container - overwrite the sizes done by Feature::initCompute ()
00122   output.points.resize (indices_->size () * input_->points.size (), 5);
00123   output.height = 1;
00124   output.width = static_cast<uint32_t> (indices_->size () * input_->points.size ());
00125 
00126   output.is_dense = true;
00127   // Compute point pair features for every pair of points in the cloud
00128   for (size_t index_i = 0; index_i < indices_->size (); ++index_i)
00129   {
00130     size_t i = (*indices_)[index_i];
00131     for (size_t j = 0 ; j < input_->points.size (); ++j)
00132     {
00133       Eigen::VectorXf p (5);
00134       if (i != j)
00135       {
00136         if (//pcl::computePPFPairFeature
00137             pcl::computePairFeatures (input_->points[i].getVector4fMap (),
00138                                       normals_->points[i].getNormalVector4fMap (),
00139                                       input_->points[j].getVector4fMap (),
00140                                       normals_->points[j].getNormalVector4fMap (),
00141                                       p (0), p (1), p (2), p (3)))
00142         {
00143           // Calculate alpha_m angle
00144           Eigen::Vector3f model_reference_point = input_->points[i].getVector3fMap (),
00145                           model_reference_normal = normals_->points[i].getNormalVector3fMap (),
00146                           model_point = input_->points[j].getVector3fMap ();
00147           Eigen::AngleAxisf rotation_mg (acosf (model_reference_normal.dot (Eigen::Vector3f::UnitX ())),
00148                                          model_reference_normal.cross (Eigen::Vector3f::UnitX ()).normalized ());
00149           Eigen::Affine3f transform_mg = Eigen::Translation3f ( rotation_mg * ((-1) * model_reference_point)) * rotation_mg;
00150 
00151           Eigen::Vector3f model_point_transformed = transform_mg * model_point;
00152           float angle = atan2f ( -model_point_transformed(2), model_point_transformed(1));
00153           if (sin (angle) * model_point_transformed(2) < 0.0f)
00154             angle *= (-1);
00155           p (4) = -angle;
00156         }
00157         else
00158         {
00159           PCL_ERROR ("[pcl::%s::computeFeature] Computing pair feature vector between points %zu and %zu went wrong.\n", getClassName ().c_str (), i, j);
00160           p.setConstant (std::numeric_limits<float>::quiet_NaN ());
00161           output.is_dense = false;
00162         }
00163       }
00164       // Do not calculate the feature for identity pairs (i, i) as they are not used
00165       // in the following computations
00166       else
00167       {
00168         p.setConstant (std::numeric_limits<float>::quiet_NaN ());
00169         output.is_dense = false;
00170       }
00171 
00172       output.points.row (index_i*input_->points.size () + j) = p;
00173     }
00174   }
00175 }
00176 
00177 
00178 #define PCL_INSTANTIATE_PPFEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::PPFEstimation<T,NT,OutT>;
00179 
00180 
00181 #endif // PCL_FEATURES_IMPL_PPF_H_


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:17:21