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 
00057 class PCL_EXPORTS NarfKeypoint : public Keypoint<PointWithRange, int>
00058 {
00059   public:
00060     // =====TYPEDEFS=====
00061     typedef Keypoint<PointWithRange, int> BaseClass;
00062     
00063     typedef Keypoint<PointWithRange, int>::PointCloudOut PointCloudOut;
00064 
00065     // =====PUBLIC STRUCTS=====
00067     struct Parameters
00068     {
00069       Parameters() : support_size(-1.0f), max_no_of_interest_points(-1), min_distance_between_interest_points(0.25f),
00070                      optimal_distance_to_high_surface_change(0.25), min_interest_value(0.45f),
00071                      min_surface_change_score(0.2f), optimal_range_image_patch_size(10),
00072                      distance_for_additional_points(0.0f), add_points_on_straight_edges(false),
00073                      do_non_maximum_suppression(true), no_of_polynomial_approximations_per_point(0),
00074                      max_no_of_threads(1), use_recursive_scale_reduction(false),
00075                      calculate_sparse_interest_image(true) {}
00076       
00077       float support_size;  
00078       int max_no_of_interest_points;  
00079       float min_distance_between_interest_points;  
00082       float optimal_distance_to_high_surface_change;  
00086       float min_interest_value;  
00087       float min_surface_change_score;  
00088       int optimal_range_image_patch_size;  
00092       // TODO:
00093       float distance_for_additional_points;  
00097       bool add_points_on_straight_edges;  
00099       bool do_non_maximum_suppression;  
00102       bool no_of_polynomial_approximations_per_point; 
00105       int max_no_of_threads;  
00106       bool use_recursive_scale_reduction;  
00108       bool calculate_sparse_interest_image;  
00110     };
00111     
00112     // =====CONSTRUCTOR & DESTRUCTOR=====
00113     NarfKeypoint (RangeImageBorderExtractor* range_image_border_extractor=NULL, float support_size=-1.0f);
00114     ~NarfKeypoint ();
00115     
00116     // =====PUBLIC METHODS=====
00118     void
00119       clearData ();
00120     
00122     void
00123       setRangeImageBorderExtractor (RangeImageBorderExtractor* range_image_border_extractor);
00124     
00126     RangeImageBorderExtractor*
00127       getRangeImageBorderExtractor ()  { return range_image_border_extractor_; }
00128     
00130     void
00131       setRangeImage (const RangeImage* range_image);
00132     
00134     float*
00135       getInterestImage () { calculateInterestImage(); return interest_image_;}
00136     
00138     const ::pcl::PointCloud<InterestPoint>&
00139       getInterestPoints () { calculateInterestPoints(); return *interest_points_;}
00140     
00142     const std::vector<bool>&
00143       getIsInterestPointImage () { calculateInterestPoints(); return is_interest_point_image_;}
00144     
00146     Parameters&
00147       getParameters () { return parameters_;}
00148     
00150     const RangeImage&
00151       getRangeImage ();
00152     
00154     void
00155       compute (PointCloudOut& output);
00156     
00157   protected:
00158     // =====PROTECTED METHODS=====
00159     void
00160       calculateScaleSpace ();
00161     void
00162       calculateInterestImage ();
00163     void
00164       calculateCompleteInterestImage ();
00165     void
00166       calculateSparseInterestImage ();
00167     void
00168       calculateInterestPoints ();
00169     //void
00170       //blurInterestImage ();
00172     virtual void
00173       detectKeypoints (PointCloudOut& output);
00174     
00175     // =====PROTECTED MEMBER VARIABLES=====
00176     using BaseClass::name_;
00177     RangeImageBorderExtractor* range_image_border_extractor_;
00178     Parameters parameters_;
00179     float* interest_image_;
00180     ::pcl::PointCloud<InterestPoint>* interest_points_;
00181     std::vector<bool> is_interest_point_image_;
00182     std::vector<RangeImage*> range_image_scale_space_;
00183     std::vector<RangeImageBorderExtractor*> border_extractor_scale_space_;
00184     std::vector<float*> interest_image_scale_space_;
00185 };
00186 
00190 inline std::ostream&
00191   operator << (std::ostream& os, const NarfKeypoint::Parameters& p)
00192 {
00193   os << PVARC(p.support_size) << PVARC(p.min_distance_between_interest_points)
00194      << PVARC(p.min_interest_value) << PVARN(p.distance_for_additional_points);
00195   return (os);
00196 }
00197 
00198 }  // end namespace pcl
00199 
00200 #endif  //#ifndef PCL_NARF_KEYPOINT_H_


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:15:46