narf_keypoint.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, 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 /* \author Bastian Steder */
00037 
00038 #ifndef PCL_NARF_KEYPOINT_H_
00039 #define PCL_NARF_KEYPOINT_H_
00040 
00041 #include <pcl/pcl_macros.h>
00042 #include <pcl/point_cloud.h>
00043 #include <pcl/point_types.h>
00044 #include <pcl/keypoints/keypoint.h>
00045 
00046 namespace pcl {
00047 
00048 // Forward declarations
00049 class RangeImage;
00050 class RangeImageBorderExtractor;
00051 
00060 class PCL_EXPORTS NarfKeypoint : public Keypoint<PointWithRange, int>
00061 {
00062   public:
00063     typedef boost::shared_ptr<NarfKeypoint> Ptr;
00064     typedef boost::shared_ptr<const NarfKeypoint> ConstPtr;
00065 
00066     // =====TYPEDEFS=====
00067     typedef Keypoint<PointWithRange, int> BaseClass;
00068     
00069     typedef Keypoint<PointWithRange, int>::PointCloudOut PointCloudOut;
00070 
00071     // =====PUBLIC STRUCTS=====
00073     struct Parameters
00074     {
00075       Parameters() : support_size(-1.0f), max_no_of_interest_points(-1), min_distance_between_interest_points(0.25f),
00076                      optimal_distance_to_high_surface_change(0.25), min_interest_value(0.45f),
00077                      min_surface_change_score(0.2f), optimal_range_image_patch_size(10),
00078                      distance_for_additional_points(0.0f), add_points_on_straight_edges(false),
00079                      do_non_maximum_suppression(true), no_of_polynomial_approximations_per_point(0),
00080                      max_no_of_threads(1), use_recursive_scale_reduction(false),
00081                      calculate_sparse_interest_image(true) {}
00082       
00083       float support_size;  
00084       int max_no_of_interest_points;  
00085       float min_distance_between_interest_points;  
00088       float optimal_distance_to_high_surface_change;  
00092       float min_interest_value;  
00093       float min_surface_change_score;  
00094       int optimal_range_image_patch_size;  
00098       // TODO:
00099       float distance_for_additional_points;  
00103       bool add_points_on_straight_edges;  
00105       bool do_non_maximum_suppression;  
00108       bool no_of_polynomial_approximations_per_point; 
00111       int max_no_of_threads;  
00112       bool use_recursive_scale_reduction;  
00114       bool calculate_sparse_interest_image;  
00116     };
00117     
00118     // =====CONSTRUCTOR & DESTRUCTOR=====
00119     NarfKeypoint (RangeImageBorderExtractor* range_image_border_extractor=NULL, float support_size=-1.0f);
00120     virtual ~NarfKeypoint ();
00121     
00122     // =====PUBLIC METHODS=====
00124     void
00125       clearData ();
00126     
00128     void
00129       setRangeImageBorderExtractor (RangeImageBorderExtractor* range_image_border_extractor);
00130     
00132     RangeImageBorderExtractor*
00133       getRangeImageBorderExtractor ()  { return range_image_border_extractor_; }
00134     
00136     void
00137       setRangeImage (const RangeImage* range_image);
00138     
00140     float*
00141       getInterestImage () { calculateInterestImage(); return interest_image_;}
00142     
00144     const ::pcl::PointCloud<InterestPoint>&
00145       getInterestPoints () { calculateInterestPoints(); return *interest_points_;}
00146     
00148     const std::vector<bool>&
00149       getIsInterestPointImage () { calculateInterestPoints(); return is_interest_point_image_;}
00150     
00152     Parameters&
00153       getParameters () { return parameters_;}
00154     
00156     const RangeImage&
00157       getRangeImage ();
00158     
00160     void
00161       compute (PointCloudOut& output);
00162     
00163   protected:
00164     // =====PROTECTED METHODS=====
00165     void
00166       calculateScaleSpace ();
00167     void
00168       calculateInterestImage ();
00169     void
00170       calculateCompleteInterestImage ();
00171     void
00172       calculateSparseInterestImage ();
00173     void
00174       calculateInterestPoints ();
00175     //void
00176       //blurInterestImage ();
00178     virtual void
00179       detectKeypoints (PointCloudOut& output);
00180     
00181     // =====PROTECTED MEMBER VARIABLES=====
00182     using BaseClass::name_;
00183     RangeImageBorderExtractor* range_image_border_extractor_;
00184     Parameters parameters_;
00185     float* interest_image_;
00186     ::pcl::PointCloud<InterestPoint>* interest_points_;
00187     std::vector<bool> is_interest_point_image_;
00188     std::vector<RangeImage*> range_image_scale_space_;
00189     std::vector<RangeImageBorderExtractor*> border_extractor_scale_space_;
00190     std::vector<float*> interest_image_scale_space_;
00191 };
00192 
00196 inline std::ostream&
00197   operator << (std::ostream& os, const NarfKeypoint::Parameters& p)
00198 {
00199   os << PVARC(p.support_size) << PVARC(p.min_distance_between_interest_points)
00200      << PVARC(p.min_interest_value) << PVARN(p.distance_for_additional_points);
00201   return (os);
00202 }
00203 
00204 }  // end namespace pcl
00205 
00206 #endif  //#ifndef PCL_NARF_KEYPOINT_H_


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:25:43