agast_2d.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  *  Copyright (c) 2012-, Open Perception, Inc.
00007  *
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of Willow Garage, Inc. nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  */
00038 
00039 #ifndef PCL_KEYPOINTS_AGAST_KEYPOINT_2D_IMPL_H_
00040 #define PCL_KEYPOINTS_AGAST_KEYPOINT_2D_IMPL_H_
00041 
00042 #include <pcl/common/io.h>
00043 
00045 template <typename PointInT, typename PointOutT, typename IntensityT> bool
00046 pcl::AgastKeypoint2DBase<PointInT, PointOutT, IntensityT>::initCompute ()
00047 {
00048   if (!pcl::Keypoint<PointInT, PointOutT>::initCompute ())
00049   {
00050     PCL_ERROR ("[pcl::%s::initCompute] init failed.!\n", name_.c_str ());
00051     return (false);
00052   }
00053 
00054   if (!input_->isOrganized ())
00055   {    
00056     PCL_ERROR ("[pcl::%s::initCompute] %s doesn't support non organized clouds!\n", name_.c_str ());
00057     return (false);
00058   }
00059 
00060   return (true);
00061 }
00062 
00064 template <typename PointInT, typename PointOutT> void
00065 pcl::AgastKeypoint2D<PointInT, PointOutT>::detectKeypoints (PointCloudOut &output)
00066 {
00067   // image size
00068   const size_t width = input_->width;
00069   const size_t height = input_->height;
00070 
00071   // destination for intensity data; will be forwarded to AGAST
00072   std::vector<unsigned char> image_data (width*height);
00073 
00074   for (size_t i = 0; i < image_data.size (); ++i)
00075     image_data[i] = static_cast<unsigned char> (intensity_ ((*input_)[i]));
00076 
00077   if (!detector_)
00078     detector_.reset (new pcl::keypoints::agast::AgastDetector7_12s (width, height, threshold_, bmax_));
00079 
00080   detector_->setMaxKeypoints (nr_max_keypoints_);
00081 
00082   if (apply_non_max_suppression_)
00083   {
00084     pcl::PointCloud<pcl::PointUV> tmp_cloud;
00085     detector_->detectKeypoints (image_data, tmp_cloud);
00086 
00087     pcl::keypoints::internal::AgastApplyNonMaxSuppresion<PointOutT> anms (
00088         image_data, tmp_cloud, detector_, output);
00089   }
00090   else
00091   {
00092     pcl::keypoints::internal::AgastDetector<PointOutT> dec (
00093         image_data, detector_, output);
00094   }
00095 
00096   // we do not change the denseness
00097   output.is_dense = true;
00098 }
00099 
00100 
00101 #define AgastKeypoint2D(T,I) template class PCL_EXPORTS pcl::AgastKeypoint2D<T,I>;
00102 #endif 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:22:32