rift.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) 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  * $Id: rift.hpp 5036 2012-03-12 08:54:15Z rusu $
00037  *
00038  */
00039 
00040 #ifndef PCL_FEATURES_IMPL_RIFT_H_
00041 #define PCL_FEATURES_IMPL_RIFT_H_
00042 
00043 #include <pcl/features/rift.h>
00044 
00046 template <typename PointInT, typename GradientT, typename PointOutT> void
00047 pcl::RIFTEstimation<PointInT, GradientT, PointOutT>::computeRIFT (
00048       const PointCloudIn &cloud, const PointCloudGradient &gradient, 
00049       int p_idx, float radius, const std::vector<int> &indices, 
00050       const std::vector<float> &sqr_distances, Eigen::MatrixXf &rift_descriptor)
00051 {
00052   if (indices.empty ())
00053   {
00054     PCL_ERROR ("[pcl::RIFTEstimation] Null indices points passed!\n");
00055     return;
00056   }
00057 
00058   // Determine the number of bins to use based on the size of rift_descriptor
00059   int nr_distance_bins = static_cast<int> (rift_descriptor.rows ());
00060   int nr_gradient_bins = static_cast<int> (rift_descriptor.cols ());
00061 
00062   // Get the center point
00063   pcl::Vector3fMapConst p0 = cloud.points[p_idx].getVector3fMap ();
00064 
00065   // Compute the RIFT descriptor
00066   rift_descriptor.setZero ();
00067   for (size_t idx = 0; idx < indices.size (); ++idx)
00068   {
00069     // Compute the gradient magnitude and orientation (relative to the center point)
00070     pcl::Vector3fMapConst point = cloud.points[indices[idx]].getVector3fMap ();
00071     Eigen::Map<const Eigen::Vector3f> gradient_vector (& (gradient.points[indices[idx]].gradient[0]));
00072 
00073     float gradient_magnitude = gradient_vector.norm ();
00074     float gradient_angle_from_center = acosf (gradient_vector.dot ((point - p0).normalized ()) / gradient_magnitude);
00075     if (!pcl_isfinite (gradient_angle_from_center))
00076       gradient_angle_from_center = 0.0;
00077 
00078     // Normalize distance and angle values to: 0.0 <= d,g < nr_distances_bins,nr_gradient_bins
00079     const float eps = std::numeric_limits<float>::epsilon ();
00080     float d = static_cast<float> (nr_distance_bins) * sqrtf (sqr_distances[idx]) / (radius + eps);
00081     float g = static_cast<float> (nr_gradient_bins) * gradient_angle_from_center / (static_cast<float> (M_PI) + eps);
00082 
00083     // Compute the bin indices that need to be updated
00084     int d_idx_min = (std::max)(static_cast<int> (ceil (d - 1)), 0);
00085     int d_idx_max = (std::min)(static_cast<int> (floor (d + 1)), nr_distance_bins - 1);
00086     int g_idx_min = static_cast<int> (ceil (g - 1));
00087     int g_idx_max = static_cast<int> (floor (g + 1));
00088 
00089     // Update the appropriate bins of the histogram 
00090     for (int g_idx = g_idx_min; g_idx <= g_idx_max; ++g_idx)  
00091     {
00092       // Because gradient orientation is cyclical, out-of-bounds values must wrap around
00093       int g_idx_wrapped = ((g_idx + nr_gradient_bins) % nr_gradient_bins); 
00094 
00095       for (int d_idx = d_idx_min; d_idx <= d_idx_max; ++d_idx)
00096       {
00097         // To avoid boundary effects, use linear interpolation when updating each bin 
00098         float w = (1.0f - fabsf (d - static_cast<float> (d_idx))) * (1.0f - fabsf (g - static_cast<float> (g_idx)));
00099 
00100         rift_descriptor (d_idx, g_idx_wrapped) += w * gradient_magnitude;
00101       }
00102     }
00103   }
00104 
00105   // Normalize the RIFT descriptor to unit magnitude
00106   rift_descriptor.normalize ();
00107 }
00108 
00109 
00111 template <typename PointInT, typename GradientT, typename PointOutT> void
00112 pcl::RIFTEstimation<PointInT, GradientT, PointOutT>::computeFeature (PointCloudOut &output)
00113 {
00114   // Make sure a search radius is set
00115   if (search_radius_ == 0.0)
00116   {
00117     PCL_ERROR ("[pcl::%s::computeFeature] The search radius must be set before computing the feature!\n",
00118                getClassName ().c_str ());
00119     output.width = output.height = 0;
00120     output.points.clear ();
00121     return;
00122   }
00123 
00124   // Make sure the RIFT descriptor has valid dimensions
00125   if (nr_gradient_bins_ <= 0)
00126   {
00127     PCL_ERROR ("[pcl::%s::computeFeature] The number of gradient bins must be greater than zero!\n",
00128                getClassName ().c_str ());
00129     output.width = output.height = 0;
00130     output.points.clear ();
00131     return;
00132   }
00133   if (nr_distance_bins_ <= 0)
00134   {
00135     PCL_ERROR ("[pcl::%s::computeFeature] The number of distance bins must be greater than zero!\n",
00136                getClassName ().c_str ());
00137     output.width = output.height = 0;
00138     output.points.clear ();
00139     return;
00140   }
00141 
00142   // Check for valid input gradient
00143   if (!gradient_)
00144   {
00145     PCL_ERROR ("[pcl::%s::computeFeature] No input gradient was given!\n", getClassName ().c_str ());
00146     output.width = output.height = 0;
00147     output.points.clear ();
00148     return;
00149   }
00150   if (gradient_->points.size () != surface_->points.size ())
00151   {
00152     PCL_ERROR ("[pcl::%s::computeFeature] ", getClassName ().c_str ());
00153     PCL_ERROR ("The number of points in the input dataset differs from the number of points in the gradient!\n");
00154     output.width = output.height = 0;
00155     output.points.clear ();
00156     return;
00157   }
00158 
00159   Eigen::MatrixXf rift_descriptor (nr_distance_bins_, nr_gradient_bins_);
00160   std::vector<int> nn_indices;
00161   std::vector<float> nn_dist_sqr;
00162  
00163   // Iterating over the entire index vector
00164   for (size_t idx = 0; idx < indices_->size (); ++idx)
00165   {
00166     // Find neighbors within the search radius
00167     tree_->radiusSearch ((*indices_)[idx], search_radius_, nn_indices, nn_dist_sqr);
00168 
00169     // Compute the RIFT descriptor
00170     computeRIFT (*surface_, *gradient_, (*indices_)[idx], static_cast<float> (search_radius_), nn_indices, nn_dist_sqr, rift_descriptor);
00171 
00172     // Copy into the resultant cloud
00173     int bin = 0;
00174     for (int g_bin = 0; g_bin < rift_descriptor.cols (); ++g_bin)
00175       for (int d_bin = 0; d_bin < rift_descriptor.rows (); ++d_bin)
00176         output.points[idx].histogram[bin++] = rift_descriptor (d_bin, g_bin);
00177   }
00178 }
00179 
00181 template <typename PointInT, typename GradientT> void
00182 pcl::RIFTEstimation<PointInT, GradientT, Eigen::MatrixXf>::computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output)
00183 {
00184   // These should be moved into initCompute ()
00185   {
00186     // Make sure a search radius is set
00187     if (search_radius_ == 0.0)
00188     {
00189       PCL_ERROR ("[pcl::%s::computeFeature] The search radius must be set before computing the feature!\n",
00190                  getClassName ().c_str ());
00191       output.width = output.height = 0;
00192       output.points.resize (0, 0);
00193       return;
00194     }
00195 
00196     // Make sure the RIFT descriptor has valid dimensions
00197     if (nr_gradient_bins_ <= 0)
00198     {
00199       PCL_ERROR ("[pcl::%s::computeFeature] The number of gradient bins must be greater than zero!\n",
00200                  getClassName ().c_str ());
00201       output.width = output.height = 0;
00202       output.points.resize (0, 0);
00203       return;
00204     }
00205     if (nr_distance_bins_ <= 0)
00206     {
00207       PCL_ERROR ("[pcl::%s::computeFeature] The number of distance bins must be greater than zero!\n",
00208                  getClassName ().c_str ());
00209       output.width = output.height = 0;
00210       output.points.resize (0, 0);
00211       return;
00212     }
00213 
00214     // Check for valid input gradient
00215     if (!gradient_)
00216     {
00217       PCL_ERROR ("[pcl::%s::computeFeature] No input gradient was given!\n", getClassName ().c_str ());
00218       output.width = output.height = 0;
00219       output.points.resize (0, 0);
00220       return;
00221     }
00222     if (gradient_->points.size () != surface_->points.size ())
00223     {
00224       PCL_ERROR ("[pcl::%s::computeFeature] ", getClassName ().c_str ());
00225       PCL_ERROR ("The number of points in the input dataset differs from the number of points in the gradient!\n");
00226       output.width = output.height = 0;
00227       output.points.resize (0, 0);
00228       return;
00229     }
00230   }
00231   
00232   output.points.resize (indices_->size (), nr_gradient_bins_ * nr_distance_bins_);
00233   Eigen::MatrixXf rift_descriptor (nr_distance_bins_, nr_gradient_bins_);
00234   std::vector<int> nn_indices;
00235   std::vector<float> nn_dist_sqr;
00236  
00237   output.is_dense = true;
00238   // Iterating over the entire index vector
00239   for (size_t idx = 0; idx < indices_->size (); ++idx)
00240   {
00241     // Find neighbors within the search radius
00242     if (tree_->radiusSearch ((*indices_)[idx], search_radius_, nn_indices, nn_dist_sqr) == 0)
00243     {
00244       output.points.row (idx).setConstant (std::numeric_limits<float>::quiet_NaN ());
00245       output.is_dense = false;
00246       continue;
00247     }
00248 
00249     // Compute the RIFT descriptor
00250     this->computeRIFT (*surface_, *gradient_, (*indices_)[idx], static_cast<float> (search_radius_), nn_indices, nn_dist_sqr, 
00251                        rift_descriptor);
00252 
00253     // Copy into the resultant cloud
00254     int bin = 0;
00255     for (int g_bin = 0; g_bin < rift_descriptor.cols (); ++g_bin)
00256       for (int d_bin = 0; d_bin < rift_descriptor.rows (); ++d_bin)
00257         output.points (idx, bin++) = rift_descriptor (d_bin, g_bin);
00258 
00259   }
00260 }
00261 
00262 #define PCL_INSTANTIATE_RIFTEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::RIFTEstimation<T,NT,OutT>;
00263 
00264 #endif    // PCL_FEATURES_IMPL_RIFT_H_ 
00265 


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