shot.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  *
00037  */
00038 
00039 #ifndef PCL_FEATURES_IMPL_SHOT_H_
00040 #define PCL_FEATURES_IMPL_SHOT_H_
00041 
00042 #include <pcl/features/shot.h>
00043 #include <pcl/features/shot_lrf.h>
00044 #include <utility>
00045 
00046 // Useful constants.
00047 #define PST_PI 3.1415926535897932384626433832795
00048 #define PST_RAD_45 0.78539816339744830961566084581988
00049 #define PST_RAD_90 1.5707963267948966192313216916398
00050 #define PST_RAD_135 2.3561944901923449288469825374596
00051 #define PST_RAD_180 PST_PI
00052 #define PST_RAD_360 6.283185307179586476925286766558
00053 #define PST_RAD_PI_7_8 2.7488935718910690836548129603691
00054 
00055 const double zeroDoubleEps15 = 1E-15;
00056 const float zeroFloatEps8 = 1E-8f;
00057 
00059 
00066 inline bool
00067 areEquals (double val1, double val2, double zeroDoubleEps = zeroDoubleEps15)
00068 {
00069   return (fabs (val1 - val2)<zeroDoubleEps);
00070 }
00071 
00073 
00080 inline bool
00081 areEquals (float val1, float val2, float zeroFloatEps = zeroFloatEps8)
00082 {
00083   return (fabs (val1 - val2)<zeroFloatEps);
00084 }
00085 
00087 template <typename PointNT, typename PointRFT> float
00088 pcl::SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::sRGB_LUT[256] = {- 1};
00089 
00091 template <typename PointNT, typename PointRFT> float
00092 pcl::SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::sXYZ_LUT[4000] = {- 1};
00093 
00095 template <typename PointNT, typename PointRFT> void
00096 pcl::SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::RGB2CIELAB (unsigned char R, unsigned char G,
00097                                                                                   unsigned char B, float &L, float &A,
00098                                                                                   float &B2)
00099 {
00100   if (sRGB_LUT[0] < 0)
00101   {
00102     for (int i = 0; i < 256; i++)
00103     {
00104       float f = static_cast<float> (i) / 255.0f;
00105       if (f > 0.04045)
00106         sRGB_LUT[i] = powf ((f + 0.055f) / 1.055f, 2.4f);
00107       else
00108         sRGB_LUT[i] = f / 12.92f;
00109     }
00110 
00111     for (int i = 0; i < 4000; i++)
00112     {
00113       float f = static_cast<float> (i) / 4000.0f;
00114       if (f > 0.008856)
00115         sXYZ_LUT[i] = static_cast<float> (powf (f, 0.3333f));
00116       else
00117         sXYZ_LUT[i] = static_cast<float>((7.787 * f) + (16.0 / 116.0));
00118     }
00119   }
00120 
00121   float fr = sRGB_LUT[R];
00122   float fg = sRGB_LUT[G];
00123   float fb = sRGB_LUT[B];
00124 
00125   // Use white = D65
00126   const float x = fr * 0.412453f + fg * 0.357580f + fb * 0.180423f;
00127   const float y = fr * 0.212671f + fg * 0.715160f + fb * 0.072169f;
00128   const float z = fr * 0.019334f + fg * 0.119193f + fb * 0.950227f;
00129 
00130   float vx = x / 0.95047f;
00131   float vy = y;
00132   float vz = z / 1.08883f;
00133 
00134   vx = sXYZ_LUT[int(vx*4000)];
00135   vy = sXYZ_LUT[int(vy*4000)];
00136   vz = sXYZ_LUT[int(vz*4000)];
00137 
00138   L = 116.0f * vy - 16.0f;
00139   if (L > 100)
00140     L = 100.0f;
00141 
00142   A = 500.0f * (vx - vy);
00143   if (A > 120)
00144     A = 120.0f;
00145   else if (A <- 120)
00146     A = -120.0f;
00147 
00148   B2 = 200.0f * (vy - vz);
00149   if (B2 > 120)
00150     B2 = 120.0f;
00151   else if (B2<- 120)
00152     B2 = -120.0f;
00153 }
00154 
00156 template <typename PointInT, typename PointNT, typename PointOutT, typename PointRFT> float
00157 pcl::SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::sRGB_LUT[256] = {- 1};
00158 
00160 template <typename PointInT, typename PointNT, typename PointOutT, typename PointRFT> float
00161 pcl::SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::sXYZ_LUT[4000] = {- 1};
00162 
00164 template <typename PointInT, typename PointNT, typename PointOutT, typename PointRFT> void
00165 pcl::SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::RGB2CIELAB (unsigned char R, unsigned char G,
00166                                                                               unsigned char B, float &L, float &A,
00167                                                                               float &B2)
00168 {
00169   if (sRGB_LUT[0] < 0)
00170   {
00171     for (int i = 0; i < 256; i++)
00172     {
00173       float f = static_cast<float> (i) / 255.0f;
00174       if (f > 0.04045)
00175         sRGB_LUT[i] = powf ((f + 0.055f) / 1.055f, 2.4f);
00176       else
00177         sRGB_LUT[i] = f / 12.92f;
00178     }
00179 
00180     for (int i = 0; i < 4000; i++)
00181     {
00182       float f = static_cast<float> (i) / 4000.0f;
00183       if (f > 0.008856)
00184         sXYZ_LUT[i] = static_cast<float> (powf (f, 0.3333f));
00185       else
00186         sXYZ_LUT[i] = static_cast<float>((7.787 * f) + (16.0 / 116.0));
00187     }
00188   }
00189 
00190   float fr = sRGB_LUT[R];
00191   float fg = sRGB_LUT[G];
00192   float fb = sRGB_LUT[B];
00193 
00194   // Use white = D65
00195   const float x = fr * 0.412453f + fg * 0.357580f + fb * 0.180423f;
00196   const float y = fr * 0.212671f + fg * 0.715160f + fb * 0.072169f;
00197   const float z = fr * 0.019334f + fg * 0.119193f + fb * 0.950227f;
00198 
00199   float vx = x / 0.95047f;
00200   float vy = y;
00201   float vz = z / 1.08883f;
00202 
00203   vx = sXYZ_LUT[int(vx*4000)];
00204   vy = sXYZ_LUT[int(vy*4000)];
00205   vz = sXYZ_LUT[int(vz*4000)];
00206 
00207   L = 116.0f * vy - 16.0f;
00208   if (L > 100)
00209     L = 100.0f;
00210 
00211   A = 500.0f * (vx - vy);
00212   if (A > 120)
00213     A = 120.0f;
00214   else if (A <- 120)
00215     A = -120.0f;
00216 
00217   B2 = 200.0f * (vy - vz);
00218   if (B2 > 120)
00219     B2 = 120.0f;
00220   else if (B2<- 120)
00221     B2 = -120.0f;
00222 }
00223 
00225 template <typename PointInT, typename PointNT, typename PointOutT, typename PointRFT> bool
00226 pcl::SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::initCompute ()
00227 {
00228   if (!FeatureFromNormals<PointInT, PointNT, PointOutT>::initCompute ())
00229   {
00230     PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ());
00231     return (false);
00232   }
00233 
00234   // SHOT cannot work with k-search
00235   if (this->getKSearch () != 0)
00236   {
00237     PCL_ERROR(
00238       "[pcl::%s::initCompute] Error! Search method set to k-neighborhood. Call setKSearch(0) and setRadiusSearch( radius ) to use this class.\n",
00239       getClassName().c_str ());
00240     return (false);
00241   }
00242 
00243   // Default LRF estimation alg: SHOTLocalReferenceFrameEstimation
00244   typename SHOTLocalReferenceFrameEstimation<PointInT, PointRFT>::Ptr lrf_estimator(new SHOTLocalReferenceFrameEstimation<PointInT, PointRFT>());
00245   lrf_estimator->setRadiusSearch (search_radius_);
00246   lrf_estimator->setInputCloud (input_);
00247   lrf_estimator->setIndices (indices_);
00248   if (!fake_surface_)
00249     lrf_estimator->setSearchSurface(surface_);
00250 
00251   if (!FeatureWithLocalReferenceFrames<PointInT, PointRFT>::initLocalReferenceFrames (indices_->size (), lrf_estimator))
00252   {
00253     PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ());
00254     return (false);
00255   }
00256 
00257   return (true);
00258 }
00259 
00261 template <typename PointInT, typename PointNT, typename PointOutT, typename PointRFT> void
00262 pcl::SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::createBinDistanceShape (
00263     int index,
00264     const std::vector<int> &indices,
00265     std::vector<double> &bin_distance_shape)
00266 {
00267   bin_distance_shape.resize (indices.size ());
00268 
00269   const PointRFT& current_frame = frames_->points[index];
00270   //if (!pcl_isfinite (current_frame.rf[0]) || !pcl_isfinite (current_frame.rf[4]) || !pcl_isfinite (current_frame.rf[11]))
00271     //return;
00272 
00273   for (size_t i_idx = 0; i_idx < indices.size (); ++i_idx)
00274   {
00275     //double cosineDesc = feat[i].rf[6]*normal[0] + feat[i].rf[7]*normal[1] + feat[i].rf[8]*normal[2];
00276     double cosineDesc = normals_->points[indices[i_idx]].getNormalVector4fMap ().dot (current_frame.z_axis.getNormalVector4fMap ());
00277 
00278     if (cosineDesc > 1.0)
00279       cosineDesc = 1.0;
00280     if (cosineDesc < - 1.0)
00281       cosineDesc = - 1.0;
00282 
00283     bin_distance_shape[i_idx] = ((1.0 + cosineDesc) * nr_shape_bins_) / 2;
00284   }
00285 }
00286 
00288 template <typename PointInT, typename PointNT, typename PointOutT, typename PointRFT> void
00289 pcl::SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::normalizeHistogram (
00290     Eigen::VectorXf &shot, int desc_length)
00291 {
00292   double acc_norm = 0;
00293   for (int j = 0; j < desc_length; j++)
00294     acc_norm += shot[j] * shot[j];
00295   acc_norm = sqrt (acc_norm);
00296   for (int j = 0; j < desc_length; j++)
00297     shot[j] /= static_cast<float> (acc_norm);
00298 }
00299 
00301 template <typename PointInT, typename PointNT, typename PointOutT, typename PointRFT> void
00302 pcl::SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::interpolateSingleChannel (
00303     const std::vector<int> &indices,
00304     const std::vector<float> &sqr_dists,
00305     const int index,
00306     std::vector<double> &binDistance,
00307     const int nr_bins,
00308     Eigen::VectorXf &shot)
00309 {
00310   const Eigen::Vector4f& central_point = (*input_)[(*indices_)[index]].getVector4fMap ();
00311   const PointRFT& current_frame = (*frames_)[index];
00312 
00313   for (size_t i_idx = 0; i_idx < indices.size (); ++i_idx)
00314   {
00315     Eigen::Vector4f delta = surface_->points[indices[i_idx]].getVector4fMap () - central_point;
00316     delta[3] = 0;
00317 
00318     // Compute the Euclidean norm
00319    double distance = sqrt (sqr_dists[i_idx]);
00320 
00321     if (areEquals (distance, 0.0))
00322       continue;
00323 
00324     double xInFeatRef = delta.dot (current_frame.x_axis.getNormalVector4fMap ());
00325     double yInFeatRef = delta.dot (current_frame.y_axis.getNormalVector4fMap ());
00326     double zInFeatRef = delta.dot (current_frame.z_axis.getNormalVector4fMap ());
00327 
00328     // To avoid numerical problems afterwards
00329     if (fabs (yInFeatRef) < 1E-30)
00330       yInFeatRef  = 0;
00331     if (fabs (xInFeatRef) < 1E-30)
00332       xInFeatRef  = 0;
00333     if (fabs (zInFeatRef) < 1E-30)
00334       zInFeatRef  = 0;
00335 
00336 
00337     unsigned char bit4 = ((yInFeatRef > 0) || ((yInFeatRef == 0.0) && (xInFeatRef < 0))) ? 1 : 0;
00338     unsigned char bit3 = static_cast<unsigned char> (((xInFeatRef > 0) || ((xInFeatRef == 0.0) && (yInFeatRef > 0))) ? !bit4 : bit4);
00339 
00340     assert (bit3 == 0 || bit3 == 1);
00341 
00342     int desc_index = (bit4<<3) + (bit3<<2);
00343 
00344     desc_index = desc_index << 1;
00345 
00346     if ((xInFeatRef * yInFeatRef > 0) || (xInFeatRef == 0.0))
00347       desc_index += (fabs (xInFeatRef) >= fabs (yInFeatRef)) ? 0 : 4;
00348     else
00349       desc_index += (fabs (xInFeatRef) > fabs (yInFeatRef)) ? 4 : 0;
00350 
00351     desc_index += zInFeatRef > 0 ? 1 : 0;
00352 
00353     // 2 RADII
00354     desc_index += (distance > radius1_2_) ? 2 : 0;
00355 
00356     int step_index = static_cast<int>(floor (binDistance[i_idx] +0.5));
00357     int volume_index = desc_index * (nr_bins+1);
00358 
00359     //Interpolation on the cosine (adjacent bins in the histogram)
00360     binDistance[i_idx] -= step_index;
00361     double intWeight = (1- fabs (binDistance[i_idx]));
00362 
00363     if (binDistance[i_idx] > 0)
00364       shot[volume_index + ((step_index+1) % nr_bins)] += static_cast<float> (binDistance[i_idx]);
00365     else
00366       shot[volume_index + ((step_index - 1 + nr_bins) % nr_bins)] += - static_cast<float> (binDistance[i_idx]);
00367 
00368     //Interpolation on the distance (adjacent husks)
00369 
00370     if (distance > radius1_2_)   //external sphere
00371     {
00372       double radiusDistance = (distance - radius3_4_) / radius1_2_;
00373 
00374       if (distance > radius3_4_) //most external sector, votes only for itself
00375         intWeight += 1 - radiusDistance;  //peso=1-d
00376       else  //3/4 of radius, votes also for the internal sphere
00377       {
00378         intWeight += 1 + radiusDistance;
00379         shot[(desc_index - 2) * (nr_bins+1) + step_index] -= static_cast<float> (radiusDistance);
00380       }
00381     }
00382     else    //internal sphere
00383     {
00384       double radiusDistance = (distance - radius1_4_) / radius1_2_;
00385 
00386       if (distance < radius1_4_) //most internal sector, votes only for itself
00387         intWeight += 1 + radiusDistance;  //weight=1-d
00388       else  //3/4 of radius, votes also for the external sphere
00389       {
00390         intWeight += 1 - radiusDistance;
00391         shot[(desc_index + 2) * (nr_bins+1) + step_index] += static_cast<float> (radiusDistance);
00392       }
00393     }
00394 
00395     //Interpolation on the inclination (adjacent vertical volumes)
00396     double inclinationCos = zInFeatRef / distance;
00397     if (inclinationCos < - 1.0)
00398       inclinationCos = - 1.0;
00399     if (inclinationCos > 1.0)
00400       inclinationCos = 1.0;
00401 
00402     double inclination = acos (inclinationCos);
00403 
00404     assert (inclination >= 0.0 && inclination <= PST_RAD_180);
00405 
00406     if (inclination > PST_RAD_90 || (fabs (inclination - PST_RAD_90) < 1e-30 && zInFeatRef <= 0))
00407     {
00408       double inclinationDistance = (inclination - PST_RAD_135) / PST_RAD_90;
00409       if (inclination > PST_RAD_135)
00410         intWeight += 1 - inclinationDistance;
00411       else
00412       {
00413         intWeight += 1 + inclinationDistance;
00414         assert ((desc_index + 1) * (nr_bins+1) + step_index >= 0 && (desc_index + 1) * (nr_bins+1) + step_index < descLength_);
00415         shot[(desc_index + 1) * (nr_bins+1) + step_index] -= static_cast<float> (inclinationDistance);
00416       }
00417     }
00418     else
00419     {
00420       double inclinationDistance = (inclination - PST_RAD_45) / PST_RAD_90;
00421       if (inclination < PST_RAD_45)
00422         intWeight += 1 + inclinationDistance;
00423       else
00424       {
00425         intWeight += 1 - inclinationDistance;
00426         assert ((desc_index - 1) * (nr_bins+1) + step_index >= 0 && (desc_index - 1) * (nr_bins+1) + step_index < descLength_);
00427         shot[(desc_index - 1) * (nr_bins+1) + step_index] += static_cast<float> (inclinationDistance);
00428       }
00429     }
00430 
00431     if (yInFeatRef != 0.0 || xInFeatRef != 0.0)
00432     {
00433       //Interpolation on the azimuth (adjacent horizontal volumes)
00434       double azimuth = atan2 (yInFeatRef, xInFeatRef);
00435 
00436       int sel = desc_index >> 2;
00437       double angularSectorSpan = PST_RAD_45;
00438       double angularSectorStart = - PST_RAD_PI_7_8;
00439 
00440       double azimuthDistance = (azimuth - (angularSectorStart + angularSectorSpan*sel)) / angularSectorSpan;
00441 
00442       assert ((azimuthDistance < 0.5 || areEquals (azimuthDistance, 0.5)) && (azimuthDistance > - 0.5 || areEquals (azimuthDistance, - 0.5)));
00443 
00444       azimuthDistance = (std::max)(- 0.5, std::min (azimuthDistance, 0.5));
00445 
00446       if (azimuthDistance > 0)
00447       {
00448         intWeight += 1 - azimuthDistance;
00449         int interp_index = (desc_index + 4) % maxAngularSectors_;
00450         assert (interp_index * (nr_bins+1) + step_index >= 0 && interp_index * (nr_bins+1) + step_index < descLength_);
00451         shot[interp_index * (nr_bins+1) + step_index] += static_cast<float> (azimuthDistance);
00452       }
00453       else
00454       {
00455         int interp_index = (desc_index - 4 + maxAngularSectors_) % maxAngularSectors_;
00456         assert (interp_index * (nr_bins+1) + step_index >= 0 && interp_index * (nr_bins+1) + step_index < descLength_);
00457         intWeight += 1 + azimuthDistance;
00458         shot[interp_index * (nr_bins+1) + step_index] -= static_cast<float> (azimuthDistance);
00459       }
00460 
00461     }
00462 
00463     assert (volume_index + step_index >= 0 &&  volume_index + step_index < descLength_);
00464     shot[volume_index + step_index] += static_cast<float> (intWeight);
00465   }
00466 }
00467 
00469 template <typename PointNT, typename PointRFT> void
00470 pcl::SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::interpolateDoubleChannel (
00471   const std::vector<int> &indices,
00472   const std::vector<float> &sqr_dists,
00473   const int index,
00474   std::vector<double> &binDistanceShape,
00475   std::vector<double> &binDistanceColor,
00476   const int nr_bins_shape,
00477   const int nr_bins_color,
00478   Eigen::VectorXf &shot)
00479 {
00480   const Eigen::Vector4f &central_point = (*input_)[(*indices_)[index]].getVector4fMap ();
00481   const PointRFT& current_frame = (*frames_)[index];
00482 
00483   int shapeToColorStride = nr_grid_sector_*(nr_bins_shape+1);
00484 
00485   for (size_t i_idx = 0; i_idx < indices.size (); ++i_idx)
00486   {
00487     Eigen::Vector4f delta = surface_->points[indices[i_idx]].getVector4fMap () - central_point;
00488     delta[3] = 0;
00489 
00490     // Compute the Euclidean norm
00491     double distance = sqrt (sqr_dists[i_idx]);
00492 
00493     if (areEquals (distance, 0.0))
00494       continue;
00495 
00496     double xInFeatRef = delta.dot (current_frame.x_axis.getNormalVector4fMap ());
00497     double yInFeatRef = delta.dot (current_frame.y_axis.getNormalVector4fMap ());
00498     double zInFeatRef = delta.dot (current_frame.z_axis.getNormalVector4fMap ());
00499 
00500     // To avoid numerical problems afterwards
00501     if (fabs (yInFeatRef) < 1E-30)
00502       yInFeatRef  = 0;
00503     if (fabs (xInFeatRef) < 1E-30)
00504       xInFeatRef  = 0;
00505     if (fabs (zInFeatRef) < 1E-30)
00506       zInFeatRef  = 0;
00507 
00508     unsigned char bit4 = ((yInFeatRef > 0) || ((yInFeatRef == 0.0) && (xInFeatRef < 0))) ? 1 : 0;
00509     unsigned char bit3 = static_cast<unsigned char> (((xInFeatRef > 0) || ((xInFeatRef == 0.0) && (yInFeatRef > 0))) ? !bit4 : bit4);
00510 
00511     assert (bit3 == 0 || bit3 == 1);
00512 
00513     int desc_index = (bit4<<3) + (bit3<<2);
00514 
00515     desc_index = desc_index << 1;
00516 
00517     if ((xInFeatRef * yInFeatRef > 0) || (xInFeatRef == 0.0))
00518       desc_index += (fabs (xInFeatRef) >= fabs (yInFeatRef)) ? 0 : 4;
00519     else
00520       desc_index += (fabs (xInFeatRef) > fabs (yInFeatRef)) ? 4 : 0;
00521 
00522     desc_index += zInFeatRef > 0 ? 1 : 0;
00523 
00524     // 2 RADII
00525     desc_index += (distance > radius1_2_) ? 2 : 0;
00526 
00527     int step_index_shape = static_cast<int>(floor (binDistanceShape[i_idx] +0.5));
00528     int step_index_color = static_cast<int>(floor (binDistanceColor[i_idx] +0.5));
00529 
00530     int volume_index_shape = desc_index * (nr_bins_shape+1);
00531     int volume_index_color = shapeToColorStride + desc_index * (nr_bins_color+1);
00532 
00533     //Interpolation on the cosine (adjacent bins in the histrogram)
00534     binDistanceShape[i_idx] -= step_index_shape;
00535     binDistanceColor[i_idx] -= step_index_color;
00536 
00537     double intWeightShape = (1- fabs (binDistanceShape[i_idx]));
00538     double intWeightColor = (1- fabs (binDistanceColor[i_idx]));
00539 
00540     if (binDistanceShape[i_idx] > 0)
00541       shot[volume_index_shape + ((step_index_shape + 1) % nr_bins_shape)] += static_cast<float> (binDistanceShape[i_idx]);
00542     else
00543       shot[volume_index_shape + ((step_index_shape - 1 + nr_bins_shape) % nr_bins_shape)] -= static_cast<float> (binDistanceShape[i_idx]);
00544 
00545     if (binDistanceColor[i_idx] > 0)
00546       shot[volume_index_color + ((step_index_color+1) % nr_bins_color)] += static_cast<float> (binDistanceColor[i_idx]);
00547     else
00548       shot[volume_index_color + ((step_index_color - 1 + nr_bins_color) % nr_bins_color)] -= static_cast<float> (binDistanceColor[i_idx]);
00549 
00550     //Interpolation on the distance (adjacent husks)
00551 
00552     if (distance > radius1_2_)   //external sphere
00553     {
00554       double radiusDistance = (distance - radius3_4_) / radius1_2_;
00555 
00556       if (distance > radius3_4_) //most external sector, votes only for itself
00557       {
00558         intWeightShape += 1 - radiusDistance; //weight=1-d
00559         intWeightColor += 1 - radiusDistance; //weight=1-d
00560       }
00561       else  //3/4 of radius, votes also for the internal sphere
00562       {
00563         intWeightShape += 1 + radiusDistance;
00564         intWeightColor += 1 + radiusDistance;
00565         shot[(desc_index - 2) * (nr_bins_shape+1) + step_index_shape] -= static_cast<float> (radiusDistance);
00566         shot[shapeToColorStride + (desc_index - 2) * (nr_bins_color+1) + step_index_color] -= static_cast<float> (radiusDistance);
00567       }
00568     }
00569     else    //internal sphere
00570     {
00571       double radiusDistance = (distance - radius1_4_) / radius1_2_;
00572 
00573       if (distance < radius1_4_) //most internal sector, votes only for itself
00574       {
00575         intWeightShape += 1 + radiusDistance;
00576         intWeightColor += 1 + radiusDistance; //weight=1-d
00577       }
00578       else  //3/4 of radius, votes also for the external sphere
00579       {
00580         intWeightShape += 1 - radiusDistance; //weight=1-d
00581         intWeightColor += 1 - radiusDistance; //weight=1-d
00582         shot[(desc_index + 2) * (nr_bins_shape+1) + step_index_shape] += static_cast<float> (radiusDistance);
00583         shot[shapeToColorStride + (desc_index + 2) * (nr_bins_color+1) + step_index_color] += static_cast<float> (radiusDistance);
00584       }
00585     }
00586 
00587     //Interpolation on the inclination (adjacent vertical volumes)
00588     double inclinationCos = zInFeatRef / distance;
00589     if (inclinationCos < - 1.0)
00590       inclinationCos = - 1.0;
00591     if (inclinationCos > 1.0)
00592       inclinationCos = 1.0;
00593 
00594     double inclination = acos (inclinationCos);
00595 
00596     assert (inclination >= 0.0 && inclination <= PST_RAD_180);
00597 
00598     if (inclination > PST_RAD_90 || (fabs (inclination - PST_RAD_90) < 1e-30 && zInFeatRef <= 0))
00599     {
00600       double inclinationDistance = (inclination - PST_RAD_135) / PST_RAD_90;
00601       if (inclination > PST_RAD_135)
00602       {
00603         intWeightShape += 1 - inclinationDistance;
00604         intWeightColor += 1 - inclinationDistance;
00605       }
00606       else
00607       {
00608         intWeightShape += 1 + inclinationDistance;
00609         intWeightColor += 1 + inclinationDistance;
00610         assert ((desc_index + 1) * (nr_bins_shape+1) + step_index_shape >= 0 && (desc_index + 1) * (nr_bins_shape+1) + step_index_shape < descLength_);
00611         assert (shapeToColorStride + (desc_index + 1) * (nr_bins_color+ 1) + step_index_color >= 0 && shapeToColorStride + (desc_index + 1) * (nr_bins_color+1) + step_index_color < descLength_);
00612         shot[(desc_index + 1) * (nr_bins_shape+1) + step_index_shape] -= static_cast<float> (inclinationDistance);
00613         shot[shapeToColorStride + (desc_index + 1) * (nr_bins_color+1) + step_index_color] -= static_cast<float> (inclinationDistance);
00614       }
00615     }
00616     else
00617     {
00618       double inclinationDistance = (inclination - PST_RAD_45) / PST_RAD_90;
00619       if (inclination < PST_RAD_45)
00620       {
00621         intWeightShape += 1 + inclinationDistance;
00622         intWeightColor += 1 + inclinationDistance;
00623       }
00624       else
00625       {
00626         intWeightShape += 1 - inclinationDistance;
00627         intWeightColor += 1 - inclinationDistance;
00628         assert ((desc_index - 1) * (nr_bins_shape+1) + step_index_shape >= 0 && (desc_index - 1) * (nr_bins_shape+1) + step_index_shape < descLength_);
00629         assert (shapeToColorStride + (desc_index - 1) * (nr_bins_color+ 1) + step_index_color >= 0 && shapeToColorStride + (desc_index - 1) * (nr_bins_color+1) + step_index_color < descLength_);
00630         shot[(desc_index - 1) * (nr_bins_shape+1) + step_index_shape] += static_cast<float> (inclinationDistance);
00631         shot[shapeToColorStride + (desc_index - 1) * (nr_bins_color+1) + step_index_color] += static_cast<float> (inclinationDistance);
00632       }
00633     }
00634 
00635     if (yInFeatRef != 0.0 || xInFeatRef != 0.0)
00636     {
00637       //Interpolation on the azimuth (adjacent horizontal volumes)
00638       double azimuth = atan2 (yInFeatRef, xInFeatRef);
00639 
00640       int sel = desc_index >> 2;
00641       double angularSectorSpan = PST_RAD_45;
00642       double angularSectorStart = - PST_RAD_PI_7_8;
00643 
00644       double azimuthDistance = (azimuth - (angularSectorStart + angularSectorSpan*sel)) / angularSectorSpan;
00645       assert ((azimuthDistance < 0.5 || areEquals (azimuthDistance, 0.5)) && (azimuthDistance > - 0.5 || areEquals (azimuthDistance, - 0.5)));
00646       azimuthDistance = (std::max)(- 0.5, std::min (azimuthDistance, 0.5));
00647 
00648       if (azimuthDistance > 0)
00649       {
00650         intWeightShape += 1 - azimuthDistance;
00651         intWeightColor += 1 - azimuthDistance;
00652         int interp_index = (desc_index + 4) % maxAngularSectors_;
00653         assert (interp_index * (nr_bins_shape+1) + step_index_shape >= 0 && interp_index * (nr_bins_shape+1) + step_index_shape < descLength_);
00654         assert (shapeToColorStride + interp_index * (nr_bins_color+1) + step_index_color >= 0 && shapeToColorStride + interp_index * (nr_bins_color+1) + step_index_color < descLength_);
00655         shot[interp_index * (nr_bins_shape+1) + step_index_shape] += static_cast<float> (azimuthDistance);
00656         shot[shapeToColorStride + interp_index * (nr_bins_color+1) + step_index_color] += static_cast<float> (azimuthDistance);
00657       }
00658       else
00659       {
00660         int interp_index = (desc_index - 4 + maxAngularSectors_) % maxAngularSectors_;
00661         intWeightShape += 1 + azimuthDistance;
00662         intWeightColor += 1 + azimuthDistance;
00663         assert (interp_index * (nr_bins_shape+1) + step_index_shape >= 0 && interp_index * (nr_bins_shape+1) + step_index_shape < descLength_);
00664         assert (shapeToColorStride + interp_index * (nr_bins_color+1) + step_index_color >= 0 && shapeToColorStride + interp_index * (nr_bins_color+1) + step_index_color < descLength_);
00665         shot[interp_index * (nr_bins_shape+1) + step_index_shape] -= static_cast<float> (azimuthDistance);
00666         shot[shapeToColorStride + interp_index * (nr_bins_color+1) + step_index_color] -= static_cast<float> (azimuthDistance);
00667       }
00668     }
00669 
00670     assert (volume_index_shape + step_index_shape >= 0 &&  volume_index_shape + step_index_shape < descLength_);
00671     assert (volume_index_color + step_index_color >= 0 &&  volume_index_color + step_index_color < descLength_);
00672     shot[volume_index_shape + step_index_shape] += static_cast<float> (intWeightShape);
00673     shot[volume_index_color + step_index_color] += static_cast<float> (intWeightColor);
00674   }
00675 }
00676 
00678 template <typename PointInT, typename PointNT, typename PointOutT, typename PointRFT> void
00679 pcl::SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::interpolateDoubleChannel (
00680   const std::vector<int> &indices,
00681   const std::vector<float> &sqr_dists,
00682   const int index,
00683   std::vector<double> &binDistanceShape,
00684   std::vector<double> &binDistanceColor,
00685   const int nr_bins_shape,
00686   const int nr_bins_color,
00687   Eigen::VectorXf &shot)
00688 {
00689   const Eigen::Vector4f &central_point = (*input_)[(*indices_)[index]].getVector4fMap ();
00690   const PointRFT& current_frame = (*frames_)[index];
00691 
00692   int shapeToColorStride = nr_grid_sector_*(nr_bins_shape+1);
00693 
00694   for (size_t i_idx = 0; i_idx < indices.size (); ++i_idx)
00695   {
00696     Eigen::Vector4f delta = surface_->points[indices[i_idx]].getVector4fMap () - central_point;
00697     delta[3] = 0;
00698 
00699     // Compute the Euclidean norm
00700     double distance = sqrt (sqr_dists[i_idx]);
00701 
00702     if (areEquals (distance, 0.0))
00703       continue;
00704 
00705     double xInFeatRef = delta.dot (current_frame.x_axis.getNormalVector4fMap ());
00706     double yInFeatRef = delta.dot (current_frame.y_axis.getNormalVector4fMap ());
00707     double zInFeatRef = delta.dot (current_frame.z_axis.getNormalVector4fMap ());
00708 
00709     // To avoid numerical problems afterwards
00710     if (fabs (yInFeatRef) < 1E-30)
00711       yInFeatRef  = 0;
00712     if (fabs (xInFeatRef) < 1E-30)
00713       xInFeatRef  = 0;
00714     if (fabs (zInFeatRef) < 1E-30)
00715       zInFeatRef  = 0;
00716 
00717     unsigned char bit4 = ((yInFeatRef > 0) || ((yInFeatRef == 0.0) && (xInFeatRef < 0))) ? 1 : 0;
00718     unsigned char bit3 = static_cast<unsigned char> (((xInFeatRef > 0) || ((xInFeatRef == 0.0) && (yInFeatRef > 0))) ? !bit4 : bit4);
00719 
00720     assert (bit3 == 0 || bit3 == 1);
00721 
00722     int desc_index = (bit4<<3) + (bit3<<2);
00723 
00724     desc_index = desc_index << 1;
00725 
00726     if ((xInFeatRef * yInFeatRef > 0) || (xInFeatRef == 0.0))
00727       desc_index += (fabs (xInFeatRef) >= fabs (yInFeatRef)) ? 0 : 4;
00728     else
00729       desc_index += (fabs (xInFeatRef) > fabs (yInFeatRef)) ? 4 : 0;
00730 
00731     desc_index += zInFeatRef > 0 ? 1 : 0;
00732 
00733     // 2 RADII
00734     desc_index += (distance > radius1_2_) ? 2 : 0;
00735 
00736     int step_index_shape = static_cast<int>(floor (binDistanceShape[i_idx] +0.5));
00737     int step_index_color = static_cast<int>(floor (binDistanceColor[i_idx] +0.5));
00738 
00739     int volume_index_shape = desc_index * (nr_bins_shape+1);
00740     int volume_index_color = shapeToColorStride + desc_index * (nr_bins_color+1);
00741 
00742     //Interpolation on the cosine (adjacent bins in the histrogram)
00743     binDistanceShape[i_idx] -= step_index_shape;
00744     binDistanceColor[i_idx] -= step_index_color;
00745 
00746     double intWeightShape = (1- fabs (binDistanceShape[i_idx]));
00747     double intWeightColor = (1- fabs (binDistanceColor[i_idx]));
00748 
00749     if (binDistanceShape[i_idx] > 0)
00750       shot[volume_index_shape + ((step_index_shape + 1) % nr_bins_shape)] += static_cast<float> (binDistanceShape[i_idx]);
00751     else
00752       shot[volume_index_shape + ((step_index_shape - 1 + nr_bins_shape) % nr_bins_shape)] -= static_cast<float> (binDistanceShape[i_idx]);
00753 
00754     if (binDistanceColor[i_idx] > 0)
00755       shot[volume_index_color + ((step_index_color+1) % nr_bins_color)] += static_cast<float> (binDistanceColor[i_idx]);
00756     else
00757       shot[volume_index_color + ((step_index_color - 1 + nr_bins_color) % nr_bins_color)] -= static_cast<float> (binDistanceColor[i_idx]);
00758 
00759     //Interpolation on the distance (adjacent husks)
00760 
00761     if (distance > radius1_2_)   //external sphere
00762     {
00763       double radiusDistance = (distance - radius3_4_) / radius1_2_;
00764 
00765       if (distance > radius3_4_) //most external sector, votes only for itself
00766       {
00767         intWeightShape += 1 - radiusDistance; //weight=1-d
00768         intWeightColor += 1 - radiusDistance; //weight=1-d
00769       }
00770       else  //3/4 of radius, votes also for the internal sphere
00771       {
00772         intWeightShape += 1 + radiusDistance;
00773         intWeightColor += 1 + radiusDistance;
00774         shot[(desc_index - 2) * (nr_bins_shape+1) + step_index_shape] -= static_cast<float> (radiusDistance);
00775         shot[shapeToColorStride + (desc_index - 2) * (nr_bins_color+1) + step_index_color] -= static_cast<float> (radiusDistance);
00776       }
00777     }
00778     else    //internal sphere
00779     {
00780       double radiusDistance = (distance - radius1_4_) / radius1_2_;
00781 
00782       if (distance < radius1_4_) //most internal sector, votes only for itself
00783       {
00784         intWeightShape += 1 + radiusDistance;
00785         intWeightColor += 1 + radiusDistance; //weight=1-d
00786       }
00787       else  //3/4 of radius, votes also for the external sphere
00788       {
00789         intWeightShape += 1 - radiusDistance; //weight=1-d
00790         intWeightColor += 1 - radiusDistance; //weight=1-d
00791         shot[(desc_index + 2) * (nr_bins_shape+1) + step_index_shape] += static_cast<float> (radiusDistance);
00792         shot[shapeToColorStride + (desc_index + 2) * (nr_bins_color+1) + step_index_color] += static_cast<float> (radiusDistance);
00793       }
00794     }
00795 
00796     //Interpolation on the inclination (adjacent vertical volumes)
00797     double inclinationCos = zInFeatRef / distance;
00798     if (inclinationCos < - 1.0)
00799       inclinationCos = - 1.0;
00800     if (inclinationCos > 1.0)
00801       inclinationCos = 1.0;
00802 
00803     double inclination = acos (inclinationCos);
00804 
00805     assert (inclination >= 0.0 && inclination <= PST_RAD_180);
00806 
00807     if (inclination > PST_RAD_90 || (fabs (inclination - PST_RAD_90) < 1e-30 && zInFeatRef <= 0))
00808     {
00809       double inclinationDistance = (inclination - PST_RAD_135) / PST_RAD_90;
00810       if (inclination > PST_RAD_135)
00811       {
00812         intWeightShape += 1 - inclinationDistance;
00813         intWeightColor += 1 - inclinationDistance;
00814       }
00815       else
00816       {
00817         intWeightShape += 1 + inclinationDistance;
00818         intWeightColor += 1 + inclinationDistance;
00819         assert ((desc_index + 1) * (nr_bins_shape+1) + step_index_shape >= 0 && (desc_index + 1) * (nr_bins_shape+1) + step_index_shape < descLength_);
00820         assert (shapeToColorStride + (desc_index + 1) * (nr_bins_color+ 1) + step_index_color >= 0 && shapeToColorStride + (desc_index + 1) * (nr_bins_color+1) + step_index_color < descLength_);
00821         shot[(desc_index + 1) * (nr_bins_shape+1) + step_index_shape] -= static_cast<float> (inclinationDistance);
00822         shot[shapeToColorStride + (desc_index + 1) * (nr_bins_color+1) + step_index_color] -= static_cast<float> (inclinationDistance);
00823       }
00824     }
00825     else
00826     {
00827       double inclinationDistance = (inclination - PST_RAD_45) / PST_RAD_90;
00828       if (inclination < PST_RAD_45)
00829       {
00830         intWeightShape += 1 + inclinationDistance;
00831         intWeightColor += 1 + inclinationDistance;
00832       }
00833       else
00834       {
00835         intWeightShape += 1 - inclinationDistance;
00836         intWeightColor += 1 - inclinationDistance;
00837         assert ((desc_index - 1) * (nr_bins_shape+1) + step_index_shape >= 0 && (desc_index - 1) * (nr_bins_shape+1) + step_index_shape < descLength_);
00838         assert (shapeToColorStride + (desc_index - 1) * (nr_bins_color+ 1) + step_index_color >= 0 && shapeToColorStride + (desc_index - 1) * (nr_bins_color+1) + step_index_color < descLength_);
00839         shot[(desc_index - 1) * (nr_bins_shape+1) + step_index_shape] += static_cast<float> (inclinationDistance);
00840         shot[shapeToColorStride + (desc_index - 1) * (nr_bins_color+1) + step_index_color] += static_cast<float> (inclinationDistance);
00841       }
00842     }
00843 
00844     if (yInFeatRef != 0.0 || xInFeatRef != 0.0)
00845     {
00846       //Interpolation on the azimuth (adjacent horizontal volumes)
00847       double azimuth = atan2 (yInFeatRef, xInFeatRef);
00848 
00849       int sel = desc_index >> 2;
00850       double angularSectorSpan = PST_RAD_45;
00851       double angularSectorStart = - PST_RAD_PI_7_8;
00852 
00853       double azimuthDistance = (azimuth - (angularSectorStart + angularSectorSpan*sel)) / angularSectorSpan;
00854       assert ((azimuthDistance < 0.5 || areEquals (azimuthDistance, 0.5)) && (azimuthDistance > - 0.5 || areEquals (azimuthDistance, - 0.5)));
00855       azimuthDistance = (std::max)(- 0.5, std::min (azimuthDistance, 0.5));
00856 
00857       if (azimuthDistance > 0)
00858       {
00859         intWeightShape += 1 - azimuthDistance;
00860         intWeightColor += 1 - azimuthDistance;
00861         int interp_index = (desc_index + 4) % maxAngularSectors_;
00862         assert (interp_index * (nr_bins_shape+1) + step_index_shape >= 0 && interp_index * (nr_bins_shape+1) + step_index_shape < descLength_);
00863         assert (shapeToColorStride + interp_index * (nr_bins_color+1) + step_index_color >= 0 && shapeToColorStride + interp_index * (nr_bins_color+1) + step_index_color < descLength_);
00864         shot[interp_index * (nr_bins_shape+1) + step_index_shape] += static_cast<float> (azimuthDistance);
00865         shot[shapeToColorStride + interp_index * (nr_bins_color+1) + step_index_color] += static_cast<float> (azimuthDistance);
00866       }
00867       else
00868       {
00869         int interp_index = (desc_index - 4 + maxAngularSectors_) % maxAngularSectors_;
00870         intWeightShape += 1 + azimuthDistance;
00871         intWeightColor += 1 + azimuthDistance;
00872         assert (interp_index * (nr_bins_shape+1) + step_index_shape >= 0 && interp_index * (nr_bins_shape+1) + step_index_shape < descLength_);
00873         assert (shapeToColorStride + interp_index * (nr_bins_color+1) + step_index_color >= 0 && shapeToColorStride + interp_index * (nr_bins_color+1) + step_index_color < descLength_);
00874         shot[interp_index * (nr_bins_shape+1) + step_index_shape] -= static_cast<float> (azimuthDistance);
00875         shot[shapeToColorStride + interp_index * (nr_bins_color+1) + step_index_color] -= static_cast<float> (azimuthDistance);
00876       }
00877     }
00878 
00879     assert (volume_index_shape + step_index_shape >= 0 &&  volume_index_shape + step_index_shape < descLength_);
00880     assert (volume_index_color + step_index_color >= 0 &&  volume_index_color + step_index_color < descLength_);
00881     shot[volume_index_shape + step_index_shape] += static_cast<float> (intWeightShape);
00882     shot[volume_index_color + step_index_color] += static_cast<float> (intWeightColor);
00883   }
00884 }
00885 
00886 
00888 template <typename PointNT, typename PointRFT> void
00889 pcl::SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::computePointSHOT (
00890   const int index, const std::vector<int> &indices, const std::vector<float> &sqr_dists, Eigen::VectorXf &shot)
00891 {
00892   // Clear the resultant shot
00893   shot.setZero ();
00894   std::vector<double> binDistanceShape;
00895   std::vector<double> binDistanceColor;
00896   size_t nNeighbors = indices.size ();
00897   //Skip the current feature if the number of its neighbors is not sufficient for its description
00898   if (nNeighbors < 5)
00899   {
00900     PCL_WARN ("[pcl::%s::computePointSHOT] Warning! Neighborhood has less than 5 vertexes. Aborting description of point with index %d\n",
00901                   getClassName ().c_str (), (*indices_)[index]);
00902 
00903         shot.setConstant(descLength_, 1, std::numeric_limits<float>::quiet_NaN () );
00904 
00905     return;
00906   }
00907 
00908   const PointRFT& current_frame = frames_->points[index];
00909   //if (!pcl_isfinite (current_frame.rf[0]) || !pcl_isfinite (current_frame.rf[4]) || !pcl_isfinite (current_frame.rf[11]))
00910     //return;
00911 
00912   //If shape description is enabled, compute the bins activated by each neighbor of the current feature in the shape histogram
00913   if (b_describe_shape_)
00914   {
00915     binDistanceShape.resize (nNeighbors);
00916 
00917     for (size_t i_idx = 0; i_idx < indices.size (); ++i_idx)
00918     {
00919       //feat[i].rf[6]*normal[0] + feat[i].rf[7]*normal[1] + feat[i].rf[8]*normal[2];
00920       double cosineDesc = normals_->points[indices[i_idx]].getNormalVector4fMap ().dot (current_frame.z_axis.getNormalVector4fMap ());
00921 
00922       if (cosineDesc > 1.0)
00923         cosineDesc = 1.0;
00924       if (cosineDesc < - 1.0)
00925         cosineDesc = - 1.0;
00926 
00927       binDistanceShape[i_idx] = ((1.0 + cosineDesc) * nr_shape_bins_) / 2;
00928     }
00929   }
00930 
00931   //If color description is enabled, compute the bins activated by each neighbor of the current feature in the color histogram
00932   if (b_describe_color_)
00933   {
00934     binDistanceColor.resize (nNeighbors);
00935 
00936     unsigned char redRef = input_->points[(*indices_)[index]].rgba >> 16 & 0xFF;
00937     unsigned char greenRef = input_->points[(*indices_)[index]].rgba >> 8& 0xFF;
00938     unsigned char blueRef = input_->points[(*indices_)[index]].rgba & 0xFF;
00939 
00940     float LRef, aRef, bRef;
00941 
00942     RGB2CIELAB (redRef, greenRef, blueRef, LRef, aRef, bRef);
00943     LRef /= 100.0f;
00944     aRef /= 120.0f;
00945     bRef /= 120.0f;    //normalized LAB components (0<L<1, -1<a<1, -1<b<1)
00946 
00947     for (size_t i_idx = 0; i_idx < indices.size (); ++i_idx)
00948     {
00949       unsigned char red = surface_->points[indices[i_idx]].rgba >> 16 & 0xFF;
00950       unsigned char green = surface_->points[indices[i_idx]].rgba >> 8 & 0xFF;
00951       unsigned char blue = surface_->points[indices[i_idx]].rgba & 0xFF;
00952 
00953       float L, a, b;
00954 
00955       RGB2CIELAB (red, green, blue, L, a, b);
00956       L /= 100.0f;
00957       a /= 120.0f;
00958       b /= 120.0f;   //normalized LAB components (0<L<1, -1<a<1, -1<b<1)
00959 
00960       double colorDistance = (fabs (LRef - L) + ((fabs (aRef - a) + fabs (bRef - b)) / 2)) /3;
00961 
00962       if (colorDistance > 1.0)
00963         colorDistance = 1.0;
00964       if (colorDistance < 0.0)
00965         colorDistance = 0.0;
00966 
00967       binDistanceColor[i_idx] = colorDistance * nr_color_bins_;
00968     }
00969   }
00970 
00971   //Apply quadrilinear interpolation on the activated bins in the shape and/or color histogram(s)
00972 
00973   if (b_describe_shape_ && b_describe_color_)
00974     interpolateDoubleChannel (indices, sqr_dists, index, binDistanceShape, binDistanceColor,
00975                               nr_shape_bins_, nr_color_bins_,
00976                               shot);
00977   else if (b_describe_color_)
00978     interpolateSingleChannel (indices, sqr_dists, index, binDistanceColor, nr_color_bins_, shot);
00979   else
00980     interpolateSingleChannel (indices, sqr_dists, index, binDistanceShape, nr_shape_bins_, shot);
00981 
00982   // Normalize the final histogram
00983   this->normalizeHistogram (shot, descLength_);
00984 }
00985 
00987 template <typename PointInT, typename PointNT, typename PointOutT, typename PointRFT> void
00988 pcl::SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::computePointSHOT (
00989   const int index, const std::vector<int> &indices, const std::vector<float> &sqr_dists, Eigen::VectorXf &shot)
00990 {
00991   // Clear the resultant shot
00992   shot.setZero ();
00993   std::vector<double> binDistanceShape;
00994   std::vector<double> binDistanceColor;
00995   size_t nNeighbors = indices.size ();
00996   //Skip the current feature if the number of its neighbors is not sufficient for its description
00997   if (nNeighbors < 5)
00998   {
00999     PCL_WARN ("[pcl::%s::computePointSHOT] Warning! Neighborhood has less than 5 vertexes. Aborting description of point with index %d\n",
01000                   getClassName ().c_str (), (*indices_)[index]);
01001 
01002         shot.setConstant(descLength_, 1, std::numeric_limits<float>::quiet_NaN () );
01003 
01004     return;
01005   }
01006 
01007   const PointRFT& current_frame = frames_->points[index];
01008   //if (!pcl_isfinite (current_frame.rf[0]) || !pcl_isfinite (current_frame.rf[4]) || !pcl_isfinite (current_frame.rf[11]))
01009     //return;
01010 
01011   //If shape description is enabled, compute the bins activated by each neighbor of the current feature in the shape histogram
01012   if (b_describe_shape_)
01013   {
01014     binDistanceShape.resize (nNeighbors);
01015 
01016     for (size_t i_idx = 0; i_idx < indices.size (); ++i_idx)
01017     {
01018       //feat[i].rf[6]*normal[0] + feat[i].rf[7]*normal[1] + feat[i].rf[8]*normal[2];
01019       double cosineDesc = normals_->points[indices[i_idx]].getNormalVector4fMap ().dot (current_frame.z_axis.getNormalVector4fMap ());
01020 
01021       if (cosineDesc > 1.0)
01022         cosineDesc = 1.0;
01023       if (cosineDesc < - 1.0)
01024         cosineDesc = - 1.0;
01025 
01026       binDistanceShape[i_idx] = ((1.0 + cosineDesc) * nr_shape_bins_) / 2;
01027     }
01028   }
01029 
01030   //If color description is enabled, compute the bins activated by each neighbor of the current feature in the color histogram
01031   if (b_describe_color_)
01032   {
01033     binDistanceColor.resize (nNeighbors);
01034 
01035     //unsigned char redRef = input_->points[(*indices_)[index]].rgba >> 16 & 0xFF;
01036     //unsigned char greenRef = input_->points[(*indices_)[index]].rgba >> 8& 0xFF;
01037     //unsigned char blueRef = input_->points[(*indices_)[index]].rgba & 0xFF;
01038     unsigned char redRef = input_->points[(*indices_)[index]].r;
01039     unsigned char greenRef = input_->points[(*indices_)[index]].g;
01040     unsigned char blueRef = input_->points[(*indices_)[index]].b;
01041 
01042     float LRef, aRef, bRef;
01043 
01044     RGB2CIELAB (redRef, greenRef, blueRef, LRef, aRef, bRef);
01045     LRef /= 100.0f;
01046     aRef /= 120.0f;
01047     bRef /= 120.0f;    //normalized LAB components (0<L<1, -1<a<1, -1<b<1)
01048 
01049     for (size_t i_idx = 0; i_idx < indices.size (); ++i_idx)
01050     {
01051       //unsigned char red = surface_->points[indices[i_idx]].rgba >> 16 & 0xFF;
01052       //unsigned char green = surface_->points[indices[i_idx]].rgba >> 8 & 0xFF;
01053       //unsigned char blue = surface_->points[indices[i_idx]].rgba & 0xFF;
01054       unsigned char red = surface_->points[indices[i_idx]].r;
01055       unsigned char green = surface_->points[indices[i_idx]].g;
01056       unsigned char blue = surface_->points[indices[i_idx]].b;
01057 
01058       float L, a, b;
01059 
01060       RGB2CIELAB (red, green, blue, L, a, b);
01061       L /= 100.0f;
01062       a /= 120.0f;
01063       b /= 120.0f;   //normalized LAB components (0<L<1, -1<a<1, -1<b<1)
01064 
01065       double colorDistance = (fabs (LRef - L) + ((fabs (aRef - a) + fabs (bRef - b)) / 2)) /3;
01066 
01067       if (colorDistance > 1.0)
01068         colorDistance = 1.0;
01069       if (colorDistance < 0.0)
01070         colorDistance = 0.0;
01071 
01072       binDistanceColor[i_idx] = colorDistance * nr_color_bins_;
01073     }
01074   }
01075 
01076   //Apply quadrilinear interpolation on the activated bins in the shape and/or color histogram(s)
01077 
01078   if (b_describe_shape_ && b_describe_color_)
01079     interpolateDoubleChannel (indices, sqr_dists, index, binDistanceShape, binDistanceColor,
01080                               nr_shape_bins_, nr_color_bins_,
01081                               shot);
01082   else if (b_describe_color_)
01083     interpolateSingleChannel (indices, sqr_dists, index, binDistanceColor, nr_color_bins_, shot);
01084   else
01085     interpolateSingleChannel (indices, sqr_dists, index, binDistanceShape, nr_shape_bins_, shot);
01086 
01087   // Normalize the final histogram
01088   this->normalizeHistogram (shot, descLength_);
01089 }
01090 
01091 
01093 template <typename PointInT, typename PointNT, typename PointRFT> void
01094 pcl::SHOTEstimation<PointInT, PointNT, pcl::SHOT, PointRFT>::computePointSHOT (
01095   const int index, const std::vector<int> &indices, const std::vector<float> &sqr_dists, Eigen::VectorXf &shot)
01096 {
01097   //Skip the current feature if the number of its neighbors is not sufficient for its description
01098   if (indices.size () < 5)
01099   {
01100     PCL_WARN ("[pcl::%s::computePointSHOT] Warning! Neighborhood has less than 5 vertexes. Aborting description of point with index %d\n",
01101                   getClassName ().c_str (), (*indices_)[index]);
01102 
01103         shot.setConstant(descLength_, 1, std::numeric_limits<float>::quiet_NaN () );
01104 
01105     return;
01106   }
01107 
01108    // Clear the resultant shot
01109   std::vector<double> binDistanceShape;
01110   this->createBinDistanceShape (index, indices, binDistanceShape);
01111 
01112   // Interpolate
01113   shot.setZero ();
01114   interpolateSingleChannel (indices, sqr_dists, index, binDistanceShape, nr_shape_bins_, shot);
01115 
01116   // Normalize the final histogram
01117   this->normalizeHistogram (shot, descLength_);
01118 }
01119 
01121 template <typename PointInT, typename PointNT, typename PointOutT, typename PointRFT> void
01122 pcl::SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT>::computePointSHOT (
01123   const int index, const std::vector<int> &indices, const std::vector<float> &sqr_dists, Eigen::VectorXf &shot)
01124 {
01125   //Skip the current feature if the number of its neighbors is not sufficient for its description
01126   if (indices.size () < 5)
01127   {
01128     PCL_WARN ("[pcl::%s::computePointSHOT] Warning! Neighborhood has less than 5 vertexes. Aborting description of point with index %d\n",
01129                   getClassName ().c_str (), (*indices_)[index]);
01130 
01131         shot.setConstant(descLength_, 1, std::numeric_limits<float>::quiet_NaN () );
01132 
01133     return;
01134   }
01135 
01136    // Clear the resultant shot
01137   std::vector<double> binDistanceShape;
01138   this->createBinDistanceShape (index, indices, binDistanceShape);
01139 
01140   // Interpolate
01141   shot.setZero ();
01142   interpolateSingleChannel (indices, sqr_dists, index, binDistanceShape, nr_shape_bins_, shot);
01143 
01144   // Normalize the final histogram
01145   this->normalizeHistogram (shot, descLength_);
01146 }
01147 
01149 //template <typename PointInT, typename PointNT, typename PointRFT> void
01150 //pcl::SHOTEstimation<PointInT, PointNT, Eigen::MatrixXf, PointRFT>::computePointSHOT (
01151   //const int index, const std::vector<int> &indices, const std::vector<float> &sqr_dists, Eigen::VectorXf &shot)
01152 //{
01154   //if (indices.size () < 5)
01155   //{
01156     //PCL_WARN ("[pcl::%s::computePointSHOT] Warning! Neighborhood has less than 5 vertexes. Aborting description of point with index %d\n",
01157                   //getClassName ().c_str (), (*indices_)[index]);
01158 //
01159         //shot.setConstant(descLength_, 1, std::numeric_limits<float>::quiet_NaN () );
01160     //return;
01161   //}
01162 //
01164   //std::vector<double> binDistanceShape;
01165   //this->createBinDistanceShape (index, indices, binDistanceShape);
01166 //
01168   //shot.setZero ();
01169   //interpolateSingleChannel (indices, sqr_dists, index, binDistanceShape, nr_shape_bins_, shot);
01170 //
01172   //this->normalizeHistogram (shot, descLength_);
01173 //}
01174 
01175 
01179 template <typename PointNT, typename PointRFT> void
01180 pcl::SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::computeFeature (PointCloudOut &output)
01181 {
01182   // Compute the current length of the descriptor
01183   descLength_ = (b_describe_shape_) ? nr_grid_sector_*(nr_shape_bins_+1) : 0;
01184   descLength_ +=   (b_describe_color_) ? nr_grid_sector_*(nr_color_bins_+1) : 0;
01185 
01186   // Useful values
01187   sqradius_ = search_radius_*search_radius_;
01188   radius3_4_ = (search_radius_*3) / 4;
01189   radius1_4_ = search_radius_ / 4;
01190   radius1_2_ = search_radius_ / 2;
01191 
01192   shot_.setZero (descLength_);
01193 
01194   //if (output.points[0].descriptor.size () != static_cast<size_t> (descLength_))
01195   for (size_t idx = 0; idx < indices_->size (); ++idx)
01196     output.points[idx].descriptor.resize (descLength_);
01197 //  if (output.points[0].size != (size_t)descLength_)
01198 //  {
01199 //    PCL_ERROR ("[pcl::%s::computeFeature] The desired descriptor size (%lu) does not match the output point type feature (%lu)! Aborting...\n", getClassName ().c_str (), descLength_, (unsigned long) output.points[0].size);
01200 //    return;
01201 //  }
01202 
01203   // Allocate enough space to hold the results
01204   // \note This resize is irrelevant for a radiusSearch ().
01205   std::vector<int> nn_indices (k_);
01206   std::vector<float> nn_dists (k_);
01207 
01208   output.is_dense = true;
01209   // Iterating over the entire index vector
01210   for (size_t idx = 0; idx < indices_->size (); ++idx)
01211   {
01212     bool lrf_is_nan = false;
01213     const PointRFT& current_frame = (*frames_)[idx];
01214     if (!pcl_isfinite (current_frame.rf[0]) ||
01215         !pcl_isfinite (current_frame.rf[4]) ||
01216         !pcl_isfinite (current_frame.rf[11]))
01217     {
01218       PCL_WARN ("[pcl::%s::computeFeature] The local reference frame is not valid! Aborting description of point with index %d\n",
01219         getClassName ().c_str (), (*indices_)[idx]);
01220       lrf_is_nan = true;
01221     }
01222 
01223     if (!isFinite ((*input_)[(*indices_)[idx]]) ||
01224         lrf_is_nan ||
01225         this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
01226     {
01227       // Copy into the resultant cloud
01228       for (int d = 0; d < shot_.size (); ++d)
01229         output.points[idx].descriptor[d] = std::numeric_limits<float>::quiet_NaN ();
01230       for (int d = 0; d < 9; ++d)
01231         output.points[idx].rf[d] = std::numeric_limits<float>::quiet_NaN ();
01232 
01233       output.is_dense = false;
01234       continue;
01235     }
01236 
01237     // Compute the SHOT descriptor for the current 3D feature
01238     computePointSHOT (static_cast<int> (idx), nn_indices, nn_dists, shot_);
01239 
01240     // Copy into the resultant cloud
01241     for (int d = 0; d < shot_.size (); ++d)
01242       output.points[idx].descriptor[d] = shot_[d];
01243     for (int d = 0; d < 9; ++d)
01244       output.points[idx].rf[d] = frames_->points[idx].rf[ (4*(d/3) + (d%3)) ];
01245   }
01246 }
01247 
01251 template <typename PointNT, typename PointRFT> void
01252 pcl::SHOTEstimation<pcl::PointXYZRGBA, PointNT, Eigen::MatrixXf, PointRFT>::computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output)
01253 {
01254   // Compute the current length of the descriptor
01255   descLength_ = (b_describe_shape_) ? nr_grid_sector_*(nr_shape_bins_+1) : 0;
01256   descLength_ +=   (b_describe_color_) ? nr_grid_sector_*(nr_color_bins_+1) : 0;
01257 
01258   // Set up the output channels
01259   output.channels["shot"].name     = "shot";
01260   output.channels["shot"].offset   = 0;
01261   output.channels["shot"].size     = 4;
01262   output.channels["shot"].count    = descLength_ + 9;
01263   output.channels["shot"].datatype = sensor_msgs::PointField::FLOAT32;
01264 
01265   // Useful values
01266   sqradius_ = search_radius_*search_radius_;
01267   radius3_4_ = (search_radius_*3) / 4;
01268   radius1_4_ = search_radius_ / 4;
01269   radius1_2_ = search_radius_ / 2;
01270 
01271   shot_.setZero (descLength_);
01272 
01273   output.points.resize (indices_->size (), descLength_ + 9);
01274 
01275   // Allocate enough space to hold the results
01276   // \note This resize is irrelevant for a radiusSearch ().
01277   std::vector<int> nn_indices (k_);
01278   std::vector<float> nn_dists (k_);
01279 
01280   output.is_dense = true;
01281   // Iterating over the entire index vector
01282   for (size_t idx = 0; idx < indices_->size (); ++idx)
01283   {
01284     bool lrf_is_nan = false;
01285     const PointRFT& current_frame = (*frames_)[idx];
01286     if (!pcl_isfinite (current_frame.rf[0]) ||
01287         !pcl_isfinite (current_frame.rf[4]) ||
01288         !pcl_isfinite (current_frame.rf[11]))
01289     {
01290       PCL_WARN ("[pcl::%s::computeFeature] The local reference frame is not valid! Aborting description of point with index %d\n",
01291         getClassName ().c_str (), (*indices_)[idx]);
01292       lrf_is_nan = true;
01293     }
01294 
01295     if (!isFinite ((*input_)[(*indices_)[idx]]) ||
01296         lrf_is_nan ||
01297         this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
01298     {
01299       output.points.row (idx).setConstant (std::numeric_limits<float>::quiet_NaN ());
01300 
01301       output.is_dense = false;
01302       continue;
01303      }
01304 
01305     // Compute the SHOT descriptor for the current 3D feature
01306     this->computePointSHOT (static_cast<int> (idx), nn_indices, nn_dists, shot_);
01307 
01308     // Copy into the resultant cloud
01309     for (int d = 0; d < shot_.size (); ++d)
01310       output.points (idx, d) = shot_[d];
01311     for (int d = 0; d < 9; ++d)
01312       output.points (idx, shot_.size () + d) = frames_->points[idx].rf[ (4*(d/3) + (d%3)) ];
01313   }
01314 }
01315 
01316 
01320 template <typename PointInT, typename PointNT, typename PointRFT> void
01321 pcl::SHOTEstimation<PointInT, PointNT, pcl::SHOT, PointRFT>::computeFeature (pcl::PointCloud<pcl::SHOT> &output)
01322 {
01323   descLength_ = nr_grid_sector_ * (nr_shape_bins_+1);
01324 
01325   sqradius_ = search_radius_ * search_radius_;
01326   radius3_4_ = (search_radius_*3) / 4;
01327   radius1_4_ = search_radius_ / 4;
01328   radius1_2_ = search_radius_ / 2;
01329 
01330   shot_.setZero (descLength_);
01331 
01332   for (size_t idx = 0; idx < indices_->size (); ++idx)
01333         output.points[idx].descriptor.resize (descLength_);
01334 //  if (output.points[0].size != (size_t)descLength_)
01335 //  {
01336 //    PCL_ERROR ("[pcl::%s::computeFeature] The desired descriptor size (%lu) does not match the output point type feature (%lu)! Aborting...\n", getClassName ().c_str (), descLength_, (unsigned long) output.points[0].size);
01337 //    return;
01338 //  }
01339 
01340   // Allocate enough space to hold the results
01341   // \note This resize is irrelevant for a radiusSearch ().
01342   std::vector<int> nn_indices (k_);
01343   std::vector<float> nn_dists (k_);
01344 
01345   output.is_dense = true;
01346   // Iterating over the entire index vector
01347   for (size_t idx = 0; idx < indices_->size (); ++idx)
01348   {
01349     bool lrf_is_nan = false;
01350     const PointRFT& current_frame = (*frames_)[idx];
01351     if (!pcl_isfinite (current_frame.rf[0]) ||
01352         !pcl_isfinite (current_frame.rf[4]) ||
01353         !pcl_isfinite (current_frame.rf[11]))
01354     {
01355       PCL_WARN ("[pcl::%s::computeFeature] The local reference frame is not valid! Aborting description of point with index %d\n",
01356         getClassName ().c_str (), (*indices_)[idx]);
01357       lrf_is_nan = true;
01358     }
01359 
01360     if (!isFinite ((*input_)[(*indices_)[idx]]) ||
01361         lrf_is_nan ||
01362         this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
01363     {
01364       // Copy into the resultant cloud
01365       for (int d = 0; d < shot_.size (); ++d)
01366         output.points[idx].descriptor[d] = std::numeric_limits<float>::quiet_NaN ();
01367       for (int d = 0; d < 9; ++d)
01368         output.points[idx].rf[d] = std::numeric_limits<float>::quiet_NaN ();
01369 
01370       output.is_dense = false;
01371       continue;
01372     }
01373 
01374     // Estimate the SHOT at each patch
01375     computePointSHOT (static_cast<int> (idx), nn_indices, nn_dists, shot_);
01376 
01377     // Copy into the resultant cloud
01378     for (int d = 0; d < shot_.size (); ++d)
01379       output.points[idx].descriptor[d] = shot_[d];
01380     for (int d = 0; d < 9; ++d)
01381       output.points[idx].rf[d] = frames_->points[idx].rf[ (4*(d/3) + (d%3)) ];
01382   }
01383 }
01384 
01388 /*
01389 template <typename PointInT, typename PointNT, typename PointRFT> void
01390 pcl::SHOTEstimationBase<PointInT, PointNT, Eigen::MatrixXf, PointRFT>::computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output)
01391 {
01392   descLength_ = nr_grid_sector_ * (nr_shape_bins_+1);
01393 
01394   // Set up the output channels
01395   output.channels["shot"].name     = "shot";
01396   output.channels["shot"].offset   = 0;
01397   output.channels["shot"].size     = 4;
01398   output.channels["shot"].count    = descLength_ + 9;
01399   output.channels["shot"].datatype = sensor_msgs::PointField::FLOAT32;
01400 
01401   sqradius_ = search_radius_ * search_radius_;
01402   radius3_4_ = (search_radius_*3) / 4;
01403   radius1_4_ = search_radius_ / 4;
01404   radius1_2_ = search_radius_ / 2;
01405 
01406   shot_.setZero (descLength_);
01407 
01408   output.points.resize (indices_->size (), descLength_ + 9);
01409 
01410   // Allocate enough space to hold the results
01411   // \note This resize is irrelevant for a radiusSearch ().
01412   std::vector<int> nn_indices (k_);
01413   std::vector<float> nn_dists (k_);
01414 
01415   output.is_dense = true;
01416   // Iterating over the entire index vector
01417   for (size_t idx = 0; idx < indices_->size (); ++idx)
01418   {
01419     bool lrf_is_nan = false;
01420     const PointRFT& current_frame = (*frames_)[idx];
01421     if (!pcl_isfinite (current_frame.rf[0]) ||
01422         !pcl_isfinite (current_frame.rf[4]) ||
01423         !pcl_isfinite (current_frame.rf[11]))
01424     {
01425       PCL_WARN ("[pcl::%s::computeFeature] The local reference frame is not valid! Aborting description of point with index %d\n",
01426         getClassName ().c_str (), (*indices_)[idx]);
01427       lrf_is_nan = true;
01428     }
01429 
01430     if (!isFinite ((*input_)[(*indices_)[idx]]) ||
01431         lrf_is_nan ||
01432         this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
01433     {
01434       output.points.row (idx).setConstant (std::numeric_limits<float>::quiet_NaN ());
01435 
01436       output.is_dense = false;
01437       continue;
01438      }
01439 
01440     // Estimate the SHOT at each patch
01441     this->computePointSHOT (static_cast<int> (idx), nn_indices, nn_dists, shot_);
01442 
01443     // Copy into the resultant cloud
01444     for (int d = 0; d < shot_.size (); ++d)
01445       output.points (idx, d) = shot_[d];
01446     for (int d = 0; d < 9; ++d)
01447       output.points (idx, shot_.size () + d) = frames_->points[idx].rf[ (4*(d/3) + (d%3)) ];
01448   }
01449 }
01450 */
01454 template <typename PointInT, typename PointNT, typename PointOutT, typename PointRFT> void
01455 pcl::SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT>::computeFeature (pcl::PointCloud<PointOutT> &output)
01456 {
01457   descLength_ = nr_grid_sector_ * (nr_shape_bins_+1);
01458 
01459   sqradius_ = search_radius_ * search_radius_;
01460   radius3_4_ = (search_radius_*3) / 4;
01461   radius1_4_ = search_radius_ / 4;
01462   radius1_2_ = search_radius_ / 2;
01463 
01464   assert(descLength_ == 352);
01465 
01466   shot_.setZero (descLength_);
01467 
01468   // Allocate enough space to hold the results
01469   // \note This resize is irrelevant for a radiusSearch ().
01470   std::vector<int> nn_indices (k_);
01471   std::vector<float> nn_dists (k_);
01472 
01473   output.is_dense = true;
01474   // Iterating over the entire index vector
01475   for (size_t idx = 0; idx < indices_->size (); ++idx)
01476   {
01477     bool lrf_is_nan = false;
01478     const PointRFT& current_frame = (*frames_)[idx];
01479     if (!pcl_isfinite (current_frame.rf[0]) ||
01480         !pcl_isfinite (current_frame.rf[4]) ||
01481         !pcl_isfinite (current_frame.rf[11]))
01482     {
01483       PCL_WARN ("[pcl::%s::computeFeature] The local reference frame is not valid! Aborting description of point with index %d\n",
01484         getClassName ().c_str (), (*indices_)[idx]);
01485       lrf_is_nan = true;
01486     }
01487 
01488     if (!isFinite ((*input_)[(*indices_)[idx]]) ||
01489         lrf_is_nan ||
01490         this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
01491     {
01492       // Copy into the resultant cloud
01493       for (int d = 0; d < descLength_; ++d)
01494         output.points[idx].descriptor[d] = std::numeric_limits<float>::quiet_NaN ();
01495       for (int d = 0; d < 9; ++d)
01496         output.points[idx].rf[d] = std::numeric_limits<float>::quiet_NaN ();
01497 
01498       output.is_dense = false;
01499       continue;
01500     }
01501 
01502     // Estimate the SHOT descriptor at each patch
01503     computePointSHOT (static_cast<int> (idx), nn_indices, nn_dists, shot_);
01504 
01505     // Copy into the resultant cloud
01506     for (int d = 0; d < descLength_; ++d)
01507       output.points[idx].descriptor[d] = shot_[d];
01508     for (int d = 0; d < 9; ++d)
01509       output.points[idx].rf[d] = frames_->points[idx].rf[ (4*(d/3) + (d%3)) ];
01510   }
01511 }
01512 
01516 template <typename PointInT, typename PointNT, typename PointRFT> void
01517 pcl::SHOTEstimation<PointInT, PointNT, Eigen::MatrixXf, PointRFT>::computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output)
01518 {
01519   descLength_ = nr_grid_sector_ * (nr_shape_bins_+1);
01520 
01521   // Set up the output channels
01522   output.channels["shot"].name     = "shot";
01523   output.channels["shot"].offset   = 0;
01524   output.channels["shot"].size     = 4;
01525   output.channels["shot"].count    = descLength_ + 9;
01526   output.channels["shot"].datatype = sensor_msgs::PointField::FLOAT32;
01527 
01528   sqradius_ = search_radius_ * search_radius_;
01529   radius3_4_ = (search_radius_*3) / 4;
01530   radius1_4_ = search_radius_ / 4;
01531   radius1_2_ = search_radius_ / 2;
01532 
01533   shot_.setZero (descLength_);
01534 
01535   output.points.resize (indices_->size (), descLength_ + 9);
01536 
01537   // Allocate enough space to hold the results
01538   // \note This resize is irrelevant for a radiusSearch ().
01539   std::vector<int> nn_indices (k_);
01540   std::vector<float> nn_dists (k_);
01541 
01542   output.is_dense = true;
01543   // Iterating over the entire index vector
01544   for (size_t idx = 0; idx < indices_->size (); ++idx)
01545   {
01546     bool lrf_is_nan = false;
01547     const PointRFT& current_frame = (*frames_)[idx];
01548     if (!pcl_isfinite (current_frame.rf[0]) ||
01549         !pcl_isfinite (current_frame.rf[4]) ||
01550         !pcl_isfinite (current_frame.rf[11]))
01551     {
01552       PCL_WARN ("[pcl::%s::computeFeature] The local reference frame is not valid! Aborting description of point with index %d\n",
01553         getClassName ().c_str (), (*indices_)[idx]);
01554       lrf_is_nan = true;
01555     }
01556 
01557     if (!isFinite ((*input_)[(*indices_)[idx]]) ||
01558         lrf_is_nan ||
01559         this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
01560     {
01561       output.points.row (idx).setConstant (std::numeric_limits<float>::quiet_NaN ());
01562 
01563       output.is_dense = false;
01564       continue;
01565      }
01566 
01567     // Estimate the SHOT at each patch
01568     this->computePointSHOT (static_cast<int> (idx), nn_indices, nn_dists, shot_);
01569 
01570     // Copy into the resultant cloud
01571     for (int d = 0; d < descLength_; ++d)
01572       output.points (idx, d) = shot_[d];
01573     for (int d = 0; d < 9; ++d)
01574       output.points (idx, shot_.size () + d) = frames_->points[idx].rf[ (4*(d/3) + (d%3)) ];
01575   }
01576 }
01577 
01581 template <typename PointInT, typename PointNT, typename PointOutT, typename PointRFT> void
01582 pcl::SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::computeFeature (pcl::PointCloud<PointOutT> &output)
01583 {
01584   // Compute the current length of the descriptor
01585   descLength_ = (b_describe_shape_) ? nr_grid_sector_*(nr_shape_bins_+1) : 0;
01586   descLength_ +=   (b_describe_color_) ? nr_grid_sector_*(nr_color_bins_+1) : 0;
01587 
01588   assert( (!b_describe_color_ && b_describe_shape_ && descLength_ == 352) ||
01589           (b_describe_color_ && !b_describe_shape_ && descLength_ == 992) ||
01590           (b_describe_color_ && b_describe_shape_ && descLength_ == 1344)
01591         );
01592 
01593   // Useful values
01594   sqradius_ = search_radius_*search_radius_;
01595   radius3_4_ = (search_radius_*3) / 4;
01596   radius1_4_ = search_radius_ / 4;
01597   radius1_2_ = search_radius_ / 2;
01598 
01599   shot_.setZero (descLength_);
01600 
01601   // Allocate enough space to hold the results
01602   // \note This resize is irrelevant for a radiusSearch ().
01603   std::vector<int> nn_indices (k_);
01604   std::vector<float> nn_dists (k_);
01605 
01606   output.is_dense = true;
01607   // Iterating over the entire index vector
01608   for (size_t idx = 0; idx < indices_->size (); ++idx)
01609   {
01610     bool lrf_is_nan = false;
01611     const PointRFT& current_frame = (*frames_)[idx];
01612     if (!pcl_isfinite (current_frame.rf[0]) ||
01613         !pcl_isfinite (current_frame.rf[4]) ||
01614         !pcl_isfinite (current_frame.rf[11]))
01615     {
01616       PCL_WARN ("[pcl::%s::computeFeature] The local reference frame is not valid! Aborting description of point with index %d\n",
01617         getClassName ().c_str (), (*indices_)[idx]);
01618       lrf_is_nan = true;
01619     }
01620 
01621     if (!isFinite ((*input_)[(*indices_)[idx]]) ||
01622         lrf_is_nan ||
01623         this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
01624     {
01625       // Copy into the resultant cloud
01626       for (int d = 0; d < descLength_; ++d)
01627         output.points[idx].descriptor[d] = std::numeric_limits<float>::quiet_NaN ();
01628       for (int d = 0; d < 9; ++d)
01629         output.points[idx].rf[d] = std::numeric_limits<float>::quiet_NaN ();
01630 
01631       output.is_dense = false;
01632       continue;
01633     }
01634 
01635     // Compute the SHOT descriptor for the current 3D feature
01636     computePointSHOT (static_cast<int> (idx), nn_indices, nn_dists, shot_);
01637 
01638     // Copy into the resultant cloud
01639     for (int d = 0; d < descLength_; ++d)
01640       output.points[idx].descriptor[d] = shot_[d];
01641     for (int d = 0; d < 9; ++d)
01642       output.points[idx].rf[d] = frames_->points[idx].rf[ (4*(d/3) + (d%3)) ];
01643   }
01644 }
01645 
01649 template <typename PointInT, typename PointNT, typename PointRFT> void
01650 pcl::SHOTColorEstimation<PointInT, PointNT, Eigen::MatrixXf, PointRFT>::computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output)
01651 {
01652   // Compute the current length of the descriptor
01653   descLength_ = (b_describe_shape_) ? nr_grid_sector_*(nr_shape_bins_+1) : 0;
01654   descLength_ +=   (b_describe_color_) ? nr_grid_sector_*(nr_color_bins_+1) : 0;
01655 
01656   // Set up the output channels
01657   output.channels["shot"].name     = "shot";
01658   output.channels["shot"].offset   = 0;
01659   output.channels["shot"].size     = 4;
01660   output.channels["shot"].count    = descLength_ + 9;
01661   output.channels["shot"].datatype = sensor_msgs::PointField::FLOAT32;
01662 
01663   // Useful values
01664   sqradius_ = search_radius_*search_radius_;
01665   radius3_4_ = (search_radius_*3) / 4;
01666   radius1_4_ = search_radius_ / 4;
01667   radius1_2_ = search_radius_ / 2;
01668 
01669   shot_.setZero (descLength_);
01670 
01671   output.points.resize (indices_->size (), descLength_ + 9);
01672 
01673   // Allocate enough space to hold the results
01674   // \note This resize is irrelevant for a radiusSearch ().
01675   std::vector<int> nn_indices (k_);
01676   std::vector<float> nn_dists (k_);
01677 
01678   output.is_dense = true;
01679   // Iterating over the entire index vector
01680   for (size_t idx = 0; idx < indices_->size (); ++idx)
01681   {
01682     bool lrf_is_nan = false;
01683     const PointRFT& current_frame = (*frames_)[idx];
01684     if (!pcl_isfinite (current_frame.rf[0]) ||
01685         !pcl_isfinite (current_frame.rf[4]) ||
01686         !pcl_isfinite (current_frame.rf[11]))
01687     {
01688       PCL_WARN ("[pcl::%s::computeFeature] The local reference frame is not valid! Aborting description of point with index %d\n",
01689         getClassName ().c_str (), (*indices_)[idx]);
01690       lrf_is_nan = true;
01691     }
01692 
01693     if (!isFinite ((*input_)[(*indices_)[idx]]) ||
01694         lrf_is_nan ||
01695         this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
01696     {
01697       output.points.row (idx).setConstant (std::numeric_limits<float>::quiet_NaN ());
01698 
01699       output.is_dense = false;
01700       continue;
01701      }
01702 
01703     // Compute the SHOT descriptor for the current 3D feature
01704     this->computePointSHOT (static_cast<int> (idx), nn_indices, nn_dists, shot_);
01705 
01706     // Copy into the resultant cloud
01707     for (int d = 0; d < descLength_; ++d)
01708       output.points (idx, d) = shot_[d];
01709     for (int d = 0; d < 9; ++d)
01710       output.points (idx, shot_.size () + d) = frames_->points[idx].rf[ (4*(d/3) + (d%3)) ];
01711   }
01712 }
01713 
01714 #define PCL_INSTANTIATE_SHOTEstimationBase(T,NT,OutT,RFT) template class PCL_EXPORTS pcl::SHOTEstimationBase<T,NT,OutT,RFT>;
01715 #define PCL_INSTANTIATE_SHOTEstimation(T,NT,OutT,RFT) template class PCL_EXPORTS pcl::SHOTEstimation<T,NT,OutT,RFT>;
01716 #define PCL_INSTANTIATE_SHOTColorEstimation(T,NT,OutT,RFT) template class PCL_EXPORTS pcl::SHOTColorEstimation<T,NT,OutT,RFT>;
01717 
01718 #endif    // PCL_FEATURES_IMPL_SHOT_H_
01719 


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