Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
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
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
00063 Narf();
00065 Narf(const Narf& other);
00067 ~Narf();
00068
00069
00071 const Narf& operator=(const Narf& other);
00072
00073
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
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
00123
00124
00125
00126 void
00127 getRotations (std::vector<float>& rotations, std::vector<float>& strengths) const;
00128
00129
00130
00131
00132
00133
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
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
00223 inline void
00224 setDescriptor (float* descriptor) { descriptor_ = descriptor;}
00226 inline void
00227 setSurfacePatch (float* surface_patch) { surface_patch_ = surface_patch;}
00228
00229
00230
00231
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
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
00259 static const std::string
00260 getHeaderKeyword () { return "NARF"; }
00261
00262
00263 const static int VERSION = 1;
00264
00265
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
00276
00277 public:
00278 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00279 };
00280 #undef NARF_DEFAULT_SURFACE_PATCH_PIXEL_SIZE
00281
00282 }
00283
00284 #include <pcl/features/impl/narf.hpp>
00285
00286 #endif //#ifndef PCL_NARF_H_