shot_omp.hpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2009, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  *
00035  */
00036 
00037 #ifndef PCL_FEATURES_IMPL_SHOT_OMP_H_
00038 #define PCL_FEATURES_IMPL_SHOT_OMP_H_
00039 
00040 #include <pcl/features/shot_omp.h>
00041 #include <pcl/common/time.h>
00042 #include <pcl/features/shot_lrf_omp.h>
00043 
00044 template<typename PointInT, typename PointNT, typename PointOutT, typename PointRFT> bool
00045 pcl::SHOTEstimationOMP<PointInT, PointNT, PointOutT, PointRFT>::initCompute ()
00046 {
00047   if (!FeatureFromNormals<PointInT, PointNT, PointOutT>::initCompute ())
00048   {
00049     PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ());
00050     return (false);
00051   }
00052 
00053   // SHOT cannot work with k-search
00054   if (this->getKSearch () != 0)
00055   {
00056     PCL_ERROR(
00057       "[pcl::%s::initCompute] Error! Search method set to k-neighborhood. Call setKSearch(0) and setRadiusSearch( radius ) to use this class.\n",
00058       getClassName().c_str ());
00059     return (false);
00060   }
00061 
00062   // Default LRF estimation alg: SHOTLocalReferenceFrameEstimationOMP
00063   typename boost::shared_ptr<SHOTLocalReferenceFrameEstimationOMP<PointInT, PointRFT> > lrf_estimator(new SHOTLocalReferenceFrameEstimationOMP<PointInT, PointRFT>());
00064   lrf_estimator->setRadiusSearch (search_radius_);
00065   lrf_estimator->setInputCloud (input_);
00066   lrf_estimator->setIndices (indices_);
00067   lrf_estimator->setNumberOfThreads(threads_);
00068 
00069   if (!fake_surface_)
00070     lrf_estimator->setSearchSurface(surface_);
00071 
00072   if (!FeatureWithLocalReferenceFrames<PointInT, PointRFT>::initLocalReferenceFrames (indices_->size (), lrf_estimator))
00073   {
00074     PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ());
00075     return (false);
00076   }
00077 
00078   return (true);
00079 }
00080 
00082 template<typename PointInT, typename PointNT, typename PointOutT, typename PointRFT> bool
00083 pcl::SHOTColorEstimationOMP<PointInT, PointNT, PointOutT, PointRFT>::initCompute ()
00084 {
00085   if (!FeatureFromNormals<PointInT, PointNT, PointOutT>::initCompute ())
00086   {
00087     PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ());
00088     return (false);
00089   }
00090 
00091   // SHOT cannot work with k-search
00092   if (this->getKSearch () != 0)
00093   {
00094     PCL_ERROR(
00095       "[pcl::%s::initCompute] Error! Search method set to k-neighborhood. Call setKSearch(0) and setRadiusSearch( radius ) to use this class.\n",
00096       getClassName().c_str ());
00097     return (false);
00098   }
00099 
00100   // Default LRF estimation alg: SHOTLocalReferenceFrameEstimationOMP
00101   typename boost::shared_ptr<SHOTLocalReferenceFrameEstimationOMP<PointInT, PointRFT> > lrf_estimator(new SHOTLocalReferenceFrameEstimationOMP<PointInT, PointRFT>());
00102   lrf_estimator->setRadiusSearch (search_radius_);
00103   lrf_estimator->setInputCloud (input_);
00104   lrf_estimator->setIndices (indices_);
00105   lrf_estimator->setNumberOfThreads(threads_);
00106 
00107   if (!fake_surface_)
00108     lrf_estimator->setSearchSurface(surface_);
00109 
00110   if (!FeatureWithLocalReferenceFrames<PointInT, PointRFT>::initLocalReferenceFrames (indices_->size (), lrf_estimator))
00111   {
00112     PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ());
00113     return (false);
00114   }
00115 
00116   return (true);
00117 }
00118 
00120 template<typename PointInT, typename PointNT, typename PointRFT> bool
00121 pcl::SHOTEstimationOMP<PointInT, PointNT, pcl::SHOT, PointRFT>::initCompute ()
00122 {
00123   if (!FeatureFromNormals<PointInT, PointNT, pcl::SHOT>::initCompute ())
00124   {
00125     PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ());
00126     return (false);
00127   }
00128 
00129   // SHOT cannot work with k-search
00130   if (this->getKSearch () != 0)
00131   {
00132     PCL_ERROR(
00133       "[pcl::%s::initCompute] Error! Search method set to k-neighborhood. Call setKSearch(0) and setRadiusSearch( radius ) to use this class.\n",
00134       getClassName().c_str ());
00135     return (false);
00136   }
00137 
00138   // Default LRF estimation alg: SHOTLocalReferenceFrameEstimationOMP
00139   typename boost::shared_ptr<SHOTLocalReferenceFrameEstimationOMP<PointInT, PointRFT> > lrf_estimator(new SHOTLocalReferenceFrameEstimationOMP<PointInT, PointRFT>());
00140   lrf_estimator->setRadiusSearch (search_radius_);
00141   lrf_estimator->setInputCloud (input_);
00142   lrf_estimator->setIndices (indices_);
00143   lrf_estimator->setNumberOfThreads(threads_);
00144 
00145   if (!fake_surface_)
00146     lrf_estimator->setSearchSurface(surface_);
00147 
00148   if (!FeatureWithLocalReferenceFrames<PointInT, PointRFT>::initLocalReferenceFrames (indices_->size (), lrf_estimator))
00149   {
00150     PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ());
00151     return (false);
00152   }
00153 
00154   return (true);
00155 }
00156 
00158 template<typename PointInT, typename PointNT, typename PointOutT, typename PointRFT> void
00159 pcl::SHOTEstimationOMP<PointInT, PointNT, PointOutT, PointRFT>::computeFeature (PointCloudOut &output)
00160 {
00161 
00162   if (threads_ < 0)
00163     threads_ = 1;
00164 
00165   descLength_ = nr_grid_sector_ * (nr_shape_bins_ + 1);
00166 
00167   sqradius_ = search_radius_ * search_radius_;
00168   radius3_4_ = (search_radius_ * 3) / 4;
00169   radius1_4_ = search_radius_ / 4;
00170   radius1_2_ = search_radius_ / 2;
00171 
00172   assert(descLength_ == 352);
00173 
00174   int data_size = static_cast<int> (indices_->size ());
00175   Eigen::VectorXf *shot = new Eigen::VectorXf[threads_];
00176 
00177   for (int i = 0; i < threads_; i++)
00178     shot[i].setZero (descLength_);
00179 
00180   output.is_dense = true;
00181   // Iterating over the entire index vector
00182   #pragma omp parallel for num_threads(threads_)
00183   for (int idx = 0; idx < data_size; ++idx)
00184   {
00185 #ifdef _OPENMP
00186     int tid = omp_get_thread_num ();
00187 #else
00188     int tid = 0;
00189 #endif
00190 
00191     bool lrf_is_nan = false;
00192     const PointRFT& current_frame = (*frames_)[idx];
00193     if (!pcl_isfinite (current_frame.rf[0]) ||
00194         !pcl_isfinite (current_frame.rf[4]) ||
00195         !pcl_isfinite (current_frame.rf[11]))
00196     {
00197       PCL_WARN ("[pcl::%s::computeFeature] The local reference frame is not valid! Aborting description of point with index %d\n",
00198         getClassName ().c_str (), (*indices_)[idx]);
00199       lrf_is_nan = true;
00200     }
00201 
00202     // Allocate enough space to hold the results
00203     // \note This resize is irrelevant for a radiusSearch ().
00204     std::vector<int> nn_indices (k_);
00205     std::vector<float> nn_dists (k_);
00206 
00207     if (!isFinite ((*input_)[(*indices_)[idx]]) || lrf_is_nan || this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices,
00208                                                                                            nn_dists) == 0)
00209     {
00210       // Copy into the resultant cloud
00211       for (int d = 0; d < shot[tid].size (); ++d)
00212         output.points[idx].descriptor[d] = std::numeric_limits<float>::quiet_NaN ();
00213       for (int d = 0; d < 9; ++d)
00214         output.points[idx].rf[d] = std::numeric_limits<float>::quiet_NaN ();
00215 
00216       output.is_dense = false;
00217       continue;
00218     }
00219 
00220     // Estimate the SHOT at each patch
00221     this->computePointSHOT (idx, nn_indices, nn_dists, shot[tid]);
00222 
00223     // Copy into the resultant cloud
00224     for (int d = 0; d < shot[tid].size (); ++d)
00225       output.points[idx].descriptor[d] = shot[tid][d];
00226     for (int d = 0; d < 9; ++d)
00227       output.points[idx].rf[d] = frames_->points[idx].rf[(4 * (d / 3) + (d % 3))];
00228   }
00229   delete[] shot;
00230 }
00231 
00233 template<typename PointInT, typename PointNT, typename PointRFT> void
00234 pcl::SHOTEstimationOMP<PointInT, PointNT, pcl::SHOT, PointRFT>::computeFeature (PointCloudOut &output)
00235 {
00236 
00237   if (threads_ < 0)
00238     threads_ = 1;
00239 
00240   descLength_ = nr_grid_sector_ * (nr_shape_bins_ + 1);
00241 
00242   sqradius_ = search_radius_ * search_radius_;
00243   radius3_4_ = (search_radius_ * 3) / 4;
00244   radius1_4_ = search_radius_ / 4;
00245   radius1_2_ = search_radius_ / 2;
00246 
00247   for (size_t idx = 0; idx < indices_->size (); ++idx)
00248     output.points[idx].descriptor.resize (descLength_);
00249 
00250   int data_size = static_cast<int> (indices_->size ());
00251   Eigen::VectorXf *shot = new Eigen::VectorXf[threads_];
00252 
00253   for (int i = 0; i < threads_; i++)
00254     shot[i].setZero (descLength_);
00255 
00256   output.is_dense = true;
00257   // Iterating over the entire index vector
00258   #pragma omp parallel for num_threads(threads_)
00259   for (int idx = 0; idx < data_size; ++idx)
00260   {
00261 #ifdef _OPENMP
00262     int tid = omp_get_thread_num ();
00263 #else
00264     int tid = 0;
00265 #endif
00266 
00267     bool lrf_is_nan = false;
00268     const PointRFT& current_frame = (*frames_)[idx];
00269     if (!pcl_isfinite (current_frame.rf[0]) ||
00270         !pcl_isfinite (current_frame.rf[4]) ||
00271         !pcl_isfinite (current_frame.rf[11]))
00272     {
00273       PCL_WARN ("[pcl::%s::computeFeature] The local reference frame is not valid! Aborting description of point with index %d\n",
00274         getClassName ().c_str (), (*indices_)[idx]);
00275       lrf_is_nan = true;
00276     }
00277 
00278     // Allocate enough space to hold the results
00279     // \note This resize is irrelevant for a radiusSearch ().
00280     std::vector<int> nn_indices (k_);
00281     std::vector<float> nn_dists (k_);
00282 
00283     if (!isFinite ((*input_)[(*indices_)[idx]]) || lrf_is_nan || this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices,
00284                                                                                            nn_dists) == 0)
00285     {
00286       // Copy into the resultant cloud
00287       for (int d = 0; d < shot[tid].size (); ++d)
00288         output.points[idx].descriptor[d] = std::numeric_limits<float>::quiet_NaN ();
00289       for (int d = 0; d < 9; ++d)
00290         output.points[idx].rf[d] = std::numeric_limits<float>::quiet_NaN ();
00291 
00292       output.is_dense = false;
00293       continue;
00294     }
00295 
00296     // Estimate the SHOT at each patch
00297     this->computePointSHOT (idx, nn_indices, nn_dists, shot[tid]);
00298 
00299     // Copy into the resultant cloud
00300     for (int d = 0; d < shot[tid].size (); ++d)
00301       output.points[idx].descriptor[d] = shot[tid][d];
00302     for (int d = 0; d < 9; ++d)
00303       output.points[idx].rf[d] = frames_->points[idx].rf[(4 * (d / 3) + (d % 3))];
00304   }
00305   delete[] shot;
00306 }
00307 
00309 template <typename PointInT, typename PointNT, typename PointOutT, typename PointRFT> void
00310 pcl::SHOTColorEstimationOMP<PointInT, PointNT, PointOutT, PointRFT>::computeFeature (PointCloudOut &output)
00311 {
00312   if (threads_ < 0)
00313     threads_ = 1;
00314 
00315   descLength_ = (b_describe_shape_) ? nr_grid_sector_ * (nr_shape_bins_ + 1) : 0;
00316   descLength_ += (b_describe_color_) ? nr_grid_sector_ * (nr_color_bins_ + 1) : 0;
00317 
00318   assert( (!b_describe_color_ && b_describe_shape_ && descLength_ == 352) ||
00319           (b_describe_color_ && !b_describe_shape_ && descLength_ == 992) ||
00320           (b_describe_color_ && b_describe_shape_ && descLength_ == 1344)
00321         );
00322 
00323   sqradius_ = search_radius_ * search_radius_;
00324   radius3_4_ = (search_radius_ * 3) / 4;
00325   radius1_4_ = search_radius_ / 4;
00326   radius1_2_ = search_radius_ / 2;
00327 
00328   int data_size = static_cast<int> (indices_->size ());
00329   Eigen::VectorXf *shot = new Eigen::VectorXf[threads_];
00330 
00331   for (int i = 0; i < threads_; i++)
00332     shot[i].setZero (descLength_);
00333 
00334   output.is_dense = true;
00335   // Iterating over the entire index vector
00336 #pragma omp parallel for num_threads(threads_)
00337   for (int idx = 0; idx < data_size; ++idx)
00338   {
00339 #ifdef _OPENMP
00340     int tid = omp_get_thread_num ();
00341 #else
00342     int tid = 0;
00343 #endif
00344     // Allocate enough space to hold the results
00345     // \note This resize is irrelevant for a radiusSearch ().
00346     std::vector<int> nn_indices (k_);
00347     std::vector<float> nn_dists (k_);
00348 
00349     bool lrf_is_nan = false;
00350     const PointRFT& current_frame = (*frames_)[idx];
00351     if (!pcl_isfinite (current_frame.rf[0]) ||
00352         !pcl_isfinite (current_frame.rf[4]) ||
00353         !pcl_isfinite (current_frame.rf[11]))
00354     {
00355       PCL_WARN ("[pcl::%s::computeFeature] The local reference frame is not valid! Aborting description of point with index %d\n",
00356         getClassName ().c_str (), (*indices_)[idx]);
00357       lrf_is_nan = true;
00358     }
00359 
00360     if (!isFinite ((*input_)[(*indices_)[idx]]) ||
00361         lrf_is_nan ||
00362         this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
00363     {
00364       // Copy into the resultant cloud
00365       for (int d = 0; d < shot[tid].size (); ++d)
00366         output.points[idx].descriptor[d] = std::numeric_limits<float>::quiet_NaN ();
00367       for (int d = 0; d < 9; ++d)
00368         output.points[idx].rf[d] = std::numeric_limits<float>::quiet_NaN ();
00369 
00370       output.is_dense = false;
00371       continue;
00372     }
00373 
00374     // Estimate the SHOT at each patch
00375     this->computePointSHOT (idx, nn_indices, nn_dists, shot[tid]);
00376 
00377     // Copy into the resultant cloud
00378     for (int d = 0; d < shot[tid].size (); ++d)
00379       output.points[idx].descriptor[d] = shot[tid][d];
00380     for (int d = 0; d < 9; ++d)
00381       output.points[idx].rf[d] = frames_->points[idx].rf[ (4*(d/3) + (d%3)) ];
00382   }
00383 
00384   delete[] shot;
00385 }
00386 
00388 template<typename PointNT, typename PointRFT> void
00389 pcl::SHOTEstimationOMP<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::computeFeature (PointCloudOut &output)
00390 {
00391   if (threads_ < 0)
00392     threads_ = 1;
00393 
00394   descLength_ = (b_describe_shape_) ? nr_grid_sector_ * (nr_shape_bins_ + 1) : 0;
00395   descLength_ += (b_describe_color_) ? nr_grid_sector_ * (nr_color_bins_ + 1) : 0;
00396 
00397   sqradius_ = search_radius_ * search_radius_;
00398   radius3_4_ = (search_radius_ * 3) / 4;
00399   radius1_4_ = search_radius_ / 4;
00400   radius1_2_ = search_radius_ / 2;
00401 
00402  //if (output.points[0].descriptor.size () != static_cast<size_t> (descLength_))
00403   for (size_t idx = 0; idx < indices_->size (); ++idx)
00404     output.points[idx].descriptor.resize (descLength_);
00405 
00406   int data_size = static_cast<int> (indices_->size ());
00407   Eigen::VectorXf *shot = new Eigen::VectorXf[threads_];
00408 
00409   for (int i = 0; i < threads_; i++)
00410     shot[i].setZero (descLength_);
00411 
00412   output.is_dense = true;
00413   // Iterating over the entire index vector
00414 #pragma omp parallel for num_threads(threads_)
00415   for (int idx = 0; idx < data_size; ++idx)
00416   {
00417 #ifdef _OPENMP
00418     int tid = omp_get_thread_num ();
00419 #else
00420     int tid = 0;
00421 #endif
00422     // Allocate enough space to hold the results
00423     // \note This resize is irrelevant for a radiusSearch ().
00424     std::vector<int> nn_indices (k_);
00425     std::vector<float> nn_dists (k_);
00426 
00427     bool lrf_is_nan = false;
00428     const PointRFT& current_frame = (*frames_)[idx];
00429     if (!pcl_isfinite (current_frame.rf[0]) ||
00430         !pcl_isfinite (current_frame.rf[4]) ||
00431         !pcl_isfinite (current_frame.rf[11]))
00432     {
00433       PCL_WARN ("[pcl::%s::computeFeature] The local reference frame is not valid! Aborting description of point with index %d\n",
00434         getClassName ().c_str (), (*indices_)[idx]);
00435       lrf_is_nan = true;
00436     }
00437 
00438     if (!isFinite ((*input_)[(*indices_)[idx]]) ||
00439         lrf_is_nan ||
00440         this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
00441     {
00442       // Copy into the resultant cloud
00443       for (int d = 0; d < shot[tid].size (); ++d)
00444         output.points[idx].descriptor[d] = std::numeric_limits<float>::quiet_NaN ();
00445       for (int d = 0; d < 9; ++d)
00446         output.points[idx].rf[d] = std::numeric_limits<float>::quiet_NaN ();
00447 
00448       output.is_dense = false;
00449       continue;
00450     }
00451 
00452     // Estimate the SHOT at each patch
00453     this->computePointSHOT (idx, nn_indices, nn_dists, shot[tid]);
00454 
00455     // Copy into the resultant cloud
00456     for (int d = 0; d < shot[tid].size (); ++d)
00457       output.points[idx].descriptor[d] = shot[tid][d];
00458     for (int d = 0; d < 9; ++d)
00459       output.points[idx].rf[d] = frames_->points[idx].rf[ (4*(d/3) + (d%3)) ];
00460   }
00461 
00462   delete[] shot;
00463 }
00464 
00465 #define PCL_INSTANTIATE_SHOTEstimationOMP(T,NT,OutT,RFT) template class PCL_EXPORTS pcl::SHOTEstimationOMP<T,NT,OutT,RFT>;
00466 #define PCL_INSTANTIATE_SHOTColorEstimationOMP(T,NT,OutT,RFT) template class PCL_EXPORTS pcl::SHOTColorEstimationOMP<T,NT,OutT,RFT>;
00467 
00468 #endif    // PCL_FEATURES_IMPL_SHOT_OMP_H_


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