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
00037
00038 #ifndef PCL_NARF_H_
00039 #define PCL_NARF_H_
00040
00041 #include <vector>
00042 #include <Eigen/Geometry>
00043 #include <pcl/common/common_headers.h>
00044 #include <pcl/point_representation.h>
00045
00046 namespace pcl {
00047
00048
00049 class RangeImage;
00050 struct InterestPoint;
00051
00052 #define NARF_DEFAULT_SURFACE_PATCH_PIXEL_SIZE 10
00053
00058 class 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 void extractFromRangeImageAndAddToList(const RangeImage& range_image, const Eigen::Vector3f& interest_point, int descriptor_size,
00076 float support_size, bool rotation_invariant, std::vector<Narf*>& feature_list);
00078 static void extractFromRangeImageAndAddToList(const RangeImage& range_image, float image_x, float image_y, int descriptor_size,
00079 float support_size, bool rotation_invariant, std::vector<Narf*>& feature_list);
00081 static void extractForInterestPoints(const RangeImage& range_image, const PointCloud<InterestPoint>& interest_points,
00082 int descriptor_size, float support_size, bool rotation_invariant, std::vector<Narf*>& feature_list);
00084 static void extractForEveryRangeImagePointAndAddToList(const RangeImage& range_image, int descriptor_size, float support_size,
00085 bool rotation_invariant, std::vector<Narf*>& feature_list);
00086
00087
00093 bool extractFromRangeImage(const RangeImage& range_image, const Eigen::Affine3f& pose, int descriptor_size, float support_size,
00094 int surface_patch_world_size=NARF_DEFAULT_SURFACE_PATCH_PIXEL_SIZE);
00095
00097 bool extractFromRangeImage(const RangeImage& range_image, float x, float y, int descriptor_size, float support_size);
00098
00100 bool extractFromRangeImage(const RangeImage& range_image, const InterestPoint& interest_point, int descriptor_size, float support_size);
00101
00103 bool extractFromRangeImage(const RangeImage& range_image, const Eigen::Vector3f& interest_point, int descriptor_size, float support_size);
00104
00107 bool extractFromRangeImageWithBestRotation(const RangeImage& range_image, const Eigen::Vector3f& interest_point,
00108 int descriptor_size, float support_size);
00109
00110
00111
00112
00113
00114 void getRotations(std::vector<float>& rotations, std::vector<float>& strengths) const;
00115
00116
00117
00118
00119
00120
00121
00122 void getRotatedVersions(const RangeImage& range_image, const std::vector<float>& rotations, std::vector<Narf*>& features) const;
00123
00125 inline float getDescriptorDistance(const Narf& other) const;
00126
00128 inline int getNoOfBeamPoints() const { return lrint(ceil(0.5f*float(surface_patch_pixel_size_))); }
00129
00131 inline void copyToNarf36(Narf36& narf36) const;
00132
00134 void saveBinary(const std::string& filename) const;
00136 void saveBinary(std::ostream& file) const;
00137
00139 void loadBinary(const std::string& filename);
00141 void loadBinary(std::istream& file);
00142
00144 bool extractDescriptor(int descriptor_size);
00145
00146
00148 inline const float* getDescriptor() const { return descriptor_;}
00150 inline float* getDescriptor() { return descriptor_;}
00152 inline const int& getDescriptorSize() const { return descriptor_size_;}
00154 inline int& getDescriptorSize() { return descriptor_size_;}
00156 inline const Eigen::Vector3f& getPosition() const { return position_;}
00158 inline Eigen::Vector3f& getPosition() { return position_;}
00160 inline const Eigen::Affine3f& getTransformation() const { return transformation_;}
00162 inline Eigen::Affine3f& getTransformation() { return transformation_;}
00164 inline const int& getSurfacePatchPixelSize() const { return surface_patch_pixel_size_;}
00166 inline int& getSurfacePatchPixelSize() { return surface_patch_pixel_size_;}
00168 inline const float& getSurfacePatchWorldSize() const { return surface_patch_world_size_;}
00170 inline float& getSurfacePatchWorldSize() { return surface_patch_world_size_;}
00172 inline const float& getSurfacePatchRotation() const { return surface_patch_rotation_;}
00174 inline float& getSurfacePatchRotation() { return surface_patch_rotation_;}
00176 inline const float* getSurfacePatch() const { return surface_patch_;}
00178 inline float* getSurfacePatch() { return surface_patch_;}
00179
00180
00182 inline void setDescriptor(float* descriptor) { descriptor_ = descriptor;}
00184 inline void setSurfacePatch(float* surface_patch) { surface_patch_ = surface_patch;}
00185
00186
00187
00188
00189 struct FeaturePointRepresentation : public PointRepresentation<Narf*>
00190 {
00191 typedef Narf* PointT;
00192 FeaturePointRepresentation(int nr_dimensions) { this->nr_dimensions_ = nr_dimensions; }
00193 virtual void copyToFloatArray (const PointT& p, float* out) const { memcpy(out, p->getDescriptor(), sizeof(*p->getDescriptor())*this->nr_dimensions_); }
00194 };
00195
00196 protected:
00197
00199 void reset();
00201 void deepCopy(const Narf& other);
00203 float* getBlurredSurfacePatch(int new_pixel_size, int blur_radius) const;
00204
00206 void saveHeader(std::ostream& file) const;
00208 int loadHeader(std::istream& file) const;
00209
00210
00211 static const std::string getHeaderKeyword() { return "NARF"; }
00212
00213
00214 const static int VERSION = 1;
00215
00216
00217 Eigen::Vector3f position_;
00218 Eigen::Affine3f transformation_;
00219 float* surface_patch_;
00220 int surface_patch_pixel_size_;
00221 float surface_patch_world_size_;
00222 float surface_patch_rotation_;
00223 float* descriptor_;
00224 int descriptor_size_;
00225
00226
00227
00228 public:
00229 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00230 };
00231 #undef NARF_DEFAULT_SURFACE_PATCH_PIXEL_SIZE
00232
00233 }
00234
00235 #include "pcl/features/narf.hpp"
00236
00237 #endif //#ifndef PCL_NARF_H_