narf.h
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, 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 the copyright holder(s) 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_NARF_H_
00040 #define PCL_NARF_H_
00041 
00042 #include <pcl/features/eigen.h>
00043 #include <pcl/common/common_headers.h>
00044 #include <pcl/point_representation.h>
00045 
00046 namespace pcl 
00047 {
00048   // Forward declarations
00049   class RangeImage;
00050   struct InterestPoint;
00051 
00052 #define NARF_DEFAULT_SURFACE_PATCH_PIXEL_SIZE 10
00053 
00063   class PCL_EXPORTS Narf
00064   {
00065     public:
00066       // =====CONSTRUCTOR & DESTRUCTOR=====
00068       Narf();
00070       Narf(const Narf& other);
00072       ~Narf();
00073       
00074       // =====Operators=====
00076       const Narf& operator=(const Narf& other);
00077 
00078       // =====STATIC=====
00080       static int max_no_of_threads;
00081 
00083       static void 
00084       extractFromRangeImageAndAddToList (const RangeImage& range_image, const Eigen::Vector3f& interest_point, int descriptor_size,
00085                                          float support_size, bool rotation_invariant, std::vector<Narf*>& feature_list);
00087       static void 
00088       extractFromRangeImageAndAddToList (const RangeImage& range_image, float image_x, float image_y, int descriptor_size,
00089                                          float support_size, bool rotation_invariant, std::vector<Narf*>& feature_list);
00091       static void 
00092       extractForInterestPoints (const RangeImage& range_image, const PointCloud<InterestPoint>& interest_points,
00093                                 int descriptor_size, float support_size, bool rotation_invariant, std::vector<Narf*>& feature_list);
00095       static void 
00096       extractForEveryRangeImagePointAndAddToList (const RangeImage& range_image, int descriptor_size, float support_size,
00097                                                   bool rotation_invariant, std::vector<Narf*>& feature_list);
00098       
00099       // =====PUBLIC METHODS=====
00105       bool 
00106       extractFromRangeImage (const RangeImage& range_image, const Eigen::Affine3f& pose, int descriptor_size, float support_size,
00107                              int surface_patch_world_size=NARF_DEFAULT_SURFACE_PATCH_PIXEL_SIZE);
00108       
00110       bool 
00111       extractFromRangeImage (const RangeImage& range_image, float x, float y, int descriptor_size, float support_size);
00112 
00114       bool 
00115       extractFromRangeImage (const RangeImage& range_image, const InterestPoint& interest_point, int descriptor_size, float support_size);
00116 
00118       bool 
00119       extractFromRangeImage (const RangeImage& range_image, const Eigen::Vector3f& interest_point, int descriptor_size, float support_size);
00120 
00123       bool 
00124       extractFromRangeImageWithBestRotation (const RangeImage& range_image, const Eigen::Vector3f& interest_point,
00125                                              int descriptor_size, float support_size);
00126       
00127       /* Get the dominant rotations of the current descriptor
00128        * \param rotations the returned rotations
00129        * \param strength values describing how pronounced the corresponding rotations are
00130        */
00131       void 
00132       getRotations (std::vector<float>& rotations, std::vector<float>& strengths) const;
00133       
00134       /* Get the feature with a different rotation around the normal
00135        * You are responsible for deleting the new features!
00136        * \param range_image the source from which the feature is extracted
00137        * \param rotations list of angles (in radians)
00138        * \param rvps returned features
00139        */
00140       void 
00141       getRotatedVersions (const RangeImage& range_image, const std::vector<float>& rotations, std::vector<Narf*>& features) const;
00142       
00144       inline float 
00145       getDescriptorDistance (const Narf& other) const;
00146       
00148       inline int 
00149       getNoOfBeamPoints () const { return (static_cast<int> (pcl_lrint (ceil (0.5f * float (surface_patch_pixel_size_))))); }
00150       
00152       inline void 
00153       copyToNarf36 (Narf36& narf36) const;
00154       
00156       void 
00157       saveBinary (const std::string& filename) const;
00159       void 
00160       saveBinary (std::ostream& file) const;
00161       
00163       void 
00164       loadBinary (const std::string& filename);
00166       void 
00167       loadBinary (std::istream& file);
00168       
00170       bool 
00171       extractDescriptor (int descriptor_size);
00172       
00173       // =====GETTERS=====
00175       inline const float* 
00176       getDescriptor () const { return descriptor_;}
00178       inline float* 
00179       getDescriptor () { return descriptor_;}
00181       inline const int& 
00182       getDescriptorSize () const { return descriptor_size_;}
00184       inline int& 
00185       getDescriptorSize () { return descriptor_size_;}
00187       inline const Eigen::Vector3f& 
00188       getPosition () const { return position_;}
00190       inline Eigen::Vector3f& 
00191       getPosition () { return position_;}
00193       inline const Eigen::Affine3f& 
00194       getTransformation () const { return transformation_;}
00196       inline Eigen::Affine3f& 
00197       getTransformation () { return transformation_;}
00199       inline const int& 
00200       getSurfacePatchPixelSize () const { return surface_patch_pixel_size_;}
00202       inline int& 
00203       getSurfacePatchPixelSize () { return surface_patch_pixel_size_;}
00205       inline const float& 
00206       getSurfacePatchWorldSize () const { return surface_patch_world_size_;}
00208       inline float& 
00209       getSurfacePatchWorldSize () { return surface_patch_world_size_;}
00211       inline const float& 
00212       getSurfacePatchRotation () const { return surface_patch_rotation_;}
00214       inline float& 
00215       getSurfacePatchRotation () { return surface_patch_rotation_;}
00217       inline const float* 
00218       getSurfacePatch () const { return surface_patch_;}
00220       inline float* 
00221       getSurfacePatch () { return surface_patch_;}
00223       inline void 
00224       freeSurfacePatch () { delete[] surface_patch_; surface_patch_=NULL; surface_patch_pixel_size_=0; }
00225       
00226       // =====SETTERS=====
00228       inline void 
00229       setDescriptor (float* descriptor) { descriptor_ = descriptor;}
00231       inline void 
00232       setSurfacePatch (float* surface_patch) { surface_patch_ = surface_patch;}
00233       
00234       // =====PUBLIC MEMBER VARIABLES=====
00235       
00236       // =====PUBLIC STRUCTS=====
00237       struct FeaturePointRepresentation : public PointRepresentation<Narf*>
00238       {
00239         typedef Narf* PointT;
00240         FeaturePointRepresentation(int nr_dimensions) { this->nr_dimensions_ = nr_dimensions; }
00242         virtual ~FeaturePointRepresentation () {}
00243         virtual void copyToFloatArray (const PointT& p, float* out) const { memcpy(out, p->getDescriptor(), sizeof(*p->getDescriptor())*this->nr_dimensions_); }
00244       };
00245       
00246     protected:
00247       // =====PROTECTED METHODS=====
00249       void 
00250       reset ();
00252       void 
00253       deepCopy (const Narf& other);
00255       float* 
00256       getBlurredSurfacePatch (int new_pixel_size, int blur_radius) const;
00257       
00259       void 
00260       saveHeader (std::ostream& file) const;
00262       int 
00263       loadHeader (std::istream& file) const;
00264       
00265       // =====PROTECTED STATIC METHODS=====
00266       static const std::string 
00267       getHeaderKeyword () { return "NARF"; }
00268       
00269       // =====PROTECTED STATIC VARIABLES=====
00270       const static int VERSION = 1;
00271 
00272       // =====PROTECTED MEMBER VARIABLES=====
00273       Eigen::Vector3f position_;
00274       Eigen::Affine3f transformation_;
00275       float* surface_patch_;
00276       int surface_patch_pixel_size_;
00277       float surface_patch_world_size_;
00278       float surface_patch_rotation_;
00279       float* descriptor_;
00280       int descriptor_size_;
00281 
00282       // =====STATIC PROTECTED=====
00283       
00284     public:
00285       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00286   };
00287 #undef NARF_DEFAULT_SURFACE_PATCH_PIXEL_SIZE
00288 
00289 }  // end namespace pcl
00290 
00291 #include <pcl/features/impl/narf.hpp>
00292 
00293 #endif  //#ifndef PCL_NARF_H_


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