shot_lrf.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) 2012, Willow Garage, Inc.
00006  *  Copyright (c) 2012-, Open Perception, Inc.
00007  *
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of the copyright holder(s) nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  * $Id$
00038  */
00039 
00040 #ifndef PCL_FEATURES_IMPL_SHOT_LRF_H_
00041 #define PCL_FEATURES_IMPL_SHOT_LRF_H_
00042 
00043 #include <utility>
00044 #include <pcl/features/shot_lrf.h>
00045 
00047 // Compute a local Reference Frame for a 3D feature; the output is stored in the "rf" matrix
00048 template<typename PointInT, typename PointOutT> float
00049 pcl::SHOTLocalReferenceFrameEstimation<PointInT, PointOutT>::getLocalRF (const int& current_point_idx, Eigen::Matrix3f &rf)
00050 {
00051   const Eigen::Vector4f& central_point = (*input_)[current_point_idx].getVector4fMap ();
00052   std::vector<int> n_indices;
00053   std::vector<float> n_sqr_distances;
00054 
00055   this->searchForNeighbors (current_point_idx, search_parameter_, n_indices, n_sqr_distances);
00056 
00057   Eigen::Matrix<double, Eigen::Dynamic, 4> vij (n_indices.size (), 4);
00058 
00059   Eigen::Matrix3d cov_m = Eigen::Matrix3d::Zero ();
00060 
00061   double distance = 0.0;
00062   double sum = 0.0;
00063 
00064   int valid_nn_points = 0;
00065 
00066   for (size_t i_idx = 0; i_idx < n_indices.size (); ++i_idx)
00067   {
00068     Eigen::Vector4f pt = surface_->points[n_indices[i_idx]].getVector4fMap ();
00069     if (pt.head<3> () == central_point.head<3> ())
00070                   continue;
00071 
00072     // Difference between current point and origin
00073     vij.row (valid_nn_points).matrix () = (pt - central_point).cast<double> ();
00074     vij (valid_nn_points, 3) = 0;
00075 
00076     distance = search_parameter_ - sqrt (n_sqr_distances[i_idx]);
00077 
00078     // Multiply vij * vij'
00079     cov_m += distance * (vij.row (valid_nn_points).head<3> ().transpose () * vij.row (valid_nn_points).head<3> ());
00080 
00081     sum += distance;
00082     valid_nn_points++;
00083   }
00084 
00085   if (valid_nn_points < 5)
00086   {
00087     //PCL_ERROR ("[pcl::%s::getLocalRF] Warning! Neighborhood has less than 5 vertexes. Aborting Local RF computation of feature point (%lf, %lf, %lf)\n", "SHOTLocalReferenceFrameEstimation", central_point[0], central_point[1], central_point[2]);
00088     rf.setConstant (std::numeric_limits<float>::quiet_NaN ());
00089 
00090     return (std::numeric_limits<float>::max ());
00091   }
00092 
00093   cov_m /= sum;
00094 
00095   Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> solver (cov_m);
00096 
00097   const double& e1c = solver.eigenvalues ()[0];
00098   const double& e2c = solver.eigenvalues ()[1];
00099   const double& e3c = solver.eigenvalues ()[2];
00100 
00101   if (!pcl_isfinite (e1c) || !pcl_isfinite (e2c) || !pcl_isfinite (e3c))
00102   {
00103     //PCL_ERROR ("[pcl::%s::getLocalRF] Warning! Eigenvectors are NaN. Aborting Local RF computation of feature point (%lf, %lf, %lf)\n", "SHOTLocalReferenceFrameEstimation", central_point[0], central_point[1], central_point[2]);
00104     rf.setConstant (std::numeric_limits<float>::quiet_NaN ());
00105 
00106     return (std::numeric_limits<float>::max ());
00107   }
00108 
00109   // Disambiguation
00110   Eigen::Vector4d v1 = Eigen::Vector4d::Zero ();
00111   Eigen::Vector4d v3 = Eigen::Vector4d::Zero ();
00112   v1.head<3> ().matrix () = solver.eigenvectors ().col (2);
00113   v3.head<3> ().matrix () = solver.eigenvectors ().col (0);
00114 
00115   int plusNormal = 0, plusTangentDirection1=0;
00116   for (int ne = 0; ne < valid_nn_points; ne++)
00117   {
00118     double dp = vij.row (ne).dot (v1);
00119     if (dp >= 0)
00120       plusTangentDirection1++;
00121 
00122     dp = vij.row (ne).dot (v3);
00123     if (dp >= 0)
00124       plusNormal++;
00125   }
00126 
00127   //TANGENT
00128   plusTangentDirection1 = 2*plusTangentDirection1 - valid_nn_points;
00129   if (plusTangentDirection1 == 0)
00130   {
00131                 int points = 5; //std::min(valid_nn_points*2/2+1, 11);
00132                 int medianIndex = valid_nn_points/2;
00133 
00134                 for (int i = -points/2; i <= points/2; i++)
00135                         if ( vij.row (medianIndex - i).dot (v1) > 0)
00136                                 plusTangentDirection1 ++;
00137 
00138                 if (plusTangentDirection1 < points/2+1)
00139                         v1 *= - 1;
00140         } 
00141   else if (plusTangentDirection1 < 0)
00142     v1 *= - 1;
00143 
00144   //Normal
00145   plusNormal = 2*plusNormal - valid_nn_points;
00146   if (plusNormal == 0)
00147   {
00148                 int points = 5; //std::min(valid_nn_points*2/2+1, 11);
00149                 int medianIndex = valid_nn_points/2;
00150 
00151                 for (int i = -points/2; i <= points/2; i++)
00152                         if ( vij.row (medianIndex - i).dot (v3) > 0)
00153                                 plusNormal ++;
00154 
00155                 if (plusNormal < points/2+1)
00156                         v3 *= - 1;
00157         } else if (plusNormal < 0)
00158     v3 *= - 1;
00159 
00160   rf.row (0).matrix () = v1.head<3> ().cast<float> ();
00161   rf.row (2).matrix () = v3.head<3> ().cast<float> ();
00162   rf.row (1).matrix () = rf.row (2).cross (rf.row (0));
00163 
00164   return (0.0f);
00165 }
00166 
00168 template <typename PointInT, typename PointOutT> void
00169 pcl::SHOTLocalReferenceFrameEstimation<PointInT, PointOutT>::computeFeature (PointCloudOut &output)
00170 {
00171   //check whether used with search radius or search k-neighbors
00172   if (this->getKSearch () != 0)
00173   {
00174     PCL_ERROR(
00175       "[pcl::%s::computeFeature] Error! Search method set to k-neighborhood. Call setKSearch(0) and setRadiusSearch( radius ) to use this class.\n",
00176       getClassName().c_str ());
00177     return;
00178   }
00179   tree_->setSortedResults (true);
00180 
00181   for (size_t i = 0; i < indices_->size (); ++i)
00182   {
00183     // point result
00184     Eigen::Matrix3f rf;
00185     PointOutT& output_rf = output[i];
00186 
00187     //output_rf.confidence = getLocalRF ((*indices_)[i], rf);
00188     //if (output_rf.confidence == std::numeric_limits<float>::max ())
00189     if (getLocalRF ((*indices_)[i], rf) == std::numeric_limits<float>::max ())
00190     {
00191       output.is_dense = false;
00192     }
00193 
00194     for (int d = 0; d < 3; ++d)
00195     {
00196       output_rf.x_axis[d] = rf.row (0)[d];
00197       output_rf.y_axis[d] = rf.row (1)[d];
00198       output_rf.z_axis[d] = rf.row (2)[d];
00199     }
00200   }
00201 }
00202 
00203 #define PCL_INSTANTIATE_SHOTLocalReferenceFrameEstimation(T,OutT) template class PCL_EXPORTS pcl::SHOTLocalReferenceFrameEstimation<T,OutT>;
00204 
00205 #endif    // PCL_FEATURES_IMPL_SHOT_LRF_H_
00206 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:33:37