narf.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 #ifndef PCL_NARF_H_
00037 #define PCL_NARF_H_
00038 
00039 #include <vector>
00040 #include <Eigen/Geometry>
00041 #include <pcl/common/common_headers.h>
00042 #include <pcl/point_representation.h>
00043 
00044 namespace pcl 
00045 {
00046   // Forward declarations
00047   class RangeImage;
00048   struct InterestPoint;
00049 
00050 #define NARF_DEFAULT_SURFACE_PATCH_PIXEL_SIZE 10
00051 
00058   class PCL_EXPORTS Narf
00059   {
00060     public:
00061       // =====CONSTRUCTOR & DESTRUCTOR=====
00063       Narf();
00065       Narf(const Narf& other);
00067       ~Narf();
00068       
00069       // =====Operators=====
00071       const Narf& operator=(const Narf& other);
00072 
00073       // =====STATIC=====
00075       static int max_no_of_threads;
00076 
00078       static void 
00079       extractFromRangeImageAndAddToList (const RangeImage& range_image, const Eigen::Vector3f& interest_point, int descriptor_size,
00080                                          float support_size, bool rotation_invariant, std::vector<Narf*>& feature_list);
00082       static void 
00083       extractFromRangeImageAndAddToList (const RangeImage& range_image, float image_x, float image_y, int descriptor_size,
00084                                          float support_size, bool rotation_invariant, std::vector<Narf*>& feature_list);
00086       static void 
00087       extractForInterestPoints (const RangeImage& range_image, const PointCloud<InterestPoint>& interest_points,
00088                                 int descriptor_size, float support_size, bool rotation_invariant, std::vector<Narf*>& feature_list);
00090       static void 
00091       extractForEveryRangeImagePointAndAddToList (const RangeImage& range_image, int descriptor_size, float support_size,
00092                                                   bool rotation_invariant, std::vector<Narf*>& feature_list);
00093       
00094       // =====PUBLIC METHODS=====
00100       bool 
00101       extractFromRangeImage (const RangeImage& range_image, const Eigen::Affine3f& pose, int descriptor_size, float support_size,
00102                              int surface_patch_world_size=NARF_DEFAULT_SURFACE_PATCH_PIXEL_SIZE);
00103       
00105       bool 
00106       extractFromRangeImage (const RangeImage& range_image, float x, float y, int descriptor_size, float support_size);
00107 
00109       bool 
00110       extractFromRangeImage (const RangeImage& range_image, const InterestPoint& interest_point, int descriptor_size, float support_size);
00111 
00113       bool 
00114       extractFromRangeImage (const RangeImage& range_image, const Eigen::Vector3f& interest_point, int descriptor_size, float support_size);
00115 
00118       bool 
00119       extractFromRangeImageWithBestRotation (const RangeImage& range_image, const Eigen::Vector3f& interest_point,
00120                                              int descriptor_size, float support_size);
00121       
00122       /* Get the dominant rotations of the current descriptor
00123        * \param rotations the returned rotations
00124        * \param strength values describing how pronounced the corresponding rotations are
00125        */
00126       void 
00127       getRotations (std::vector<float>& rotations, std::vector<float>& strengths) const;
00128       
00129       /* Get the feature with a different rotation around the normal
00130        * You are responsible for deleting the new features!
00131        * \param range_image the source from which the feature is extracted
00132        * \param rotations list of angles (in radians)
00133        * \param rvps returned features
00134        */
00135       void 
00136       getRotatedVersions (const RangeImage& range_image, const std::vector<float>& rotations, std::vector<Narf*>& features) const;
00137       
00139       inline float 
00140       getDescriptorDistance (const Narf& other) const;
00141       
00143       inline int 
00144       getNoOfBeamPoints () const { return (static_cast<int> (pcl_lrint (ceil (0.5f * float (surface_patch_pixel_size_))))); }
00145       
00147       inline void 
00148       copyToNarf36 (Narf36& narf36) const;
00149       
00151       void 
00152       saveBinary (const std::string& filename) const;
00154       void 
00155       saveBinary (std::ostream& file) const;
00156       
00158       void 
00159       loadBinary (const std::string& filename);
00161       void 
00162       loadBinary (std::istream& file);
00163       
00165       bool 
00166       extractDescriptor (int descriptor_size);
00167       
00168       // =====GETTERS=====
00170       inline const float* 
00171       getDescriptor () const { return descriptor_;}
00173       inline float* 
00174       getDescriptor () { return descriptor_;}
00176       inline const int& 
00177       getDescriptorSize () const { return descriptor_size_;}
00179       inline int& 
00180       getDescriptorSize () { return descriptor_size_;}
00182       inline const Eigen::Vector3f& 
00183       getPosition () const { return position_;}
00185       inline Eigen::Vector3f& 
00186       getPosition () { return position_;}
00188       inline const Eigen::Affine3f& 
00189       getTransformation () const { return transformation_;}
00191       inline Eigen::Affine3f& 
00192       getTransformation () { return transformation_;}
00194       inline const int& 
00195       getSurfacePatchPixelSize () const { return surface_patch_pixel_size_;}
00197       inline int& 
00198       getSurfacePatchPixelSize () { return surface_patch_pixel_size_;}
00200       inline const float& 
00201       getSurfacePatchWorldSize () const { return surface_patch_world_size_;}
00203       inline float& 
00204       getSurfacePatchWorldSize () { return surface_patch_world_size_;}
00206       inline const float& 
00207       getSurfacePatchRotation () const { return surface_patch_rotation_;}
00209       inline float& 
00210       getSurfacePatchRotation () { return surface_patch_rotation_;}
00212       inline const float* 
00213       getSurfacePatch () const { return surface_patch_;}
00215       inline float* 
00216       getSurfacePatch () { return surface_patch_;}
00218       inline void 
00219       freeSurfacePatch () { delete[] surface_patch_; surface_patch_=NULL; surface_patch_pixel_size_=0; }
00220       
00221       // =====SETTERS=====
00223       inline void 
00224       setDescriptor (float* descriptor) { descriptor_ = descriptor;}
00226       inline void 
00227       setSurfacePatch (float* surface_patch) { surface_patch_ = surface_patch;}
00228       
00229       // =====PUBLIC MEMBER VARIABLES=====
00230       
00231       // =====PUBLIC STRUCTS=====
00232       struct FeaturePointRepresentation : public PointRepresentation<Narf*>
00233       {
00234         typedef Narf* PointT;
00235         FeaturePointRepresentation(int nr_dimensions) { this->nr_dimensions_ = nr_dimensions; }
00236         virtual void copyToFloatArray (const PointT& p, float* out) const { memcpy(out, p->getDescriptor(), sizeof(*p->getDescriptor())*this->nr_dimensions_); }
00237       };
00238       
00239     protected:
00240       // =====PROTECTED METHODS=====
00242       void 
00243       reset ();
00245       void 
00246       deepCopy (const Narf& other);
00248       float* 
00249       getBlurredSurfacePatch (int new_pixel_size, int blur_radius) const;
00250       
00252       void 
00253       saveHeader (std::ostream& file) const;
00255       int 
00256       loadHeader (std::istream& file) const;
00257       
00258       // =====PROTECTED STATIC METHODS=====
00259       static const std::string 
00260       getHeaderKeyword () { return "NARF"; }
00261       
00262       // =====PROTECTED STATIC VARIABLES=====
00263       const static int VERSION = 1;
00264 
00265       // =====PROTECTED MEMBER VARIABLES=====
00266       Eigen::Vector3f position_;
00267       Eigen::Affine3f transformation_;
00268       float* surface_patch_;
00269       int surface_patch_pixel_size_;
00270       float surface_patch_world_size_;
00271       float surface_patch_rotation_;
00272       float* descriptor_;
00273       int descriptor_size_;
00274 
00275       // =====STATIC PROTECTED=====
00276       
00277     public:
00278       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00279   };
00280 #undef NARF_DEFAULT_SURFACE_PATCH_PIXEL_SIZE
00281 
00282 }  // end namespace pcl
00283 
00284 #include <pcl/features/impl/narf.hpp>
00285 
00286 #endif  //#ifndef PCL_NARF_H_


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