Classes | Public Member Functions | Static Public Member Functions | Static Public Attributes | Protected Member Functions | Static Protected Member Functions | Protected Attributes | Static Protected Attributes
pcl::Narf Class Reference

NARF (Normal Aligned Radial Features) is a point feature descriptor type for 3D data. Please refer to pcl/features/narf_descriptor.h if you want the class derived from pcl Feature. More...

#include <narf.h>

List of all members.

Classes

struct  FeaturePointRepresentation

Public Member Functions

void copyToNarf36 (Narf36 &narf36) const
 Copy the descriptor and pose to the point struct Narf36.
bool extractDescriptor (int descriptor_size)
 Create the descriptor from the already set other members.
bool extractFromRangeImage (const RangeImage &range_image, const Eigen::Affine3f &pose, int descriptor_size, float support_size, int surface_patch_world_size=NARF_DEFAULT_SURFACE_PATCH_PIXEL_SIZE)
bool extractFromRangeImage (const RangeImage &range_image, float x, float y, int descriptor_size, float support_size)
 Same as above, but determines the transformation from the surface in the range image.
bool extractFromRangeImage (const RangeImage &range_image, const InterestPoint &interest_point, int descriptor_size, float support_size)
 Same as above.
bool extractFromRangeImage (const RangeImage &range_image, const Eigen::Vector3f &interest_point, int descriptor_size, float support_size)
 Same as above.
bool extractFromRangeImageWithBestRotation (const RangeImage &range_image, const Eigen::Vector3f &interest_point, int descriptor_size, float support_size)
void freeSurfacePatch ()
 Method to erase the surface patch and free the memory.
const float * getDescriptor () const
 Getter (const) for the descriptor.
float * getDescriptor ()
 Getter for the descriptor.
float getDescriptorDistance (const Narf &other) const
 Calculate descriptor distance, value in [0,1] with 0 meaning identical and 1 every cell above maximum distance.
const int & getDescriptorSize () const
 Getter (const) for the descriptor length.
int & getDescriptorSize ()
 Getter for the descriptor length.
int getNoOfBeamPoints () const
 How many points on each beam of the gradient star are used to calculate the descriptor?
const Eigen::Vector3f & getPosition () const
 Getter (const) for the position.
Eigen::Vector3f & getPosition ()
 Getter for the position.
void getRotatedVersions (const RangeImage &range_image, const std::vector< float > &rotations, std::vector< Narf * > &features) const
void getRotations (std::vector< float > &rotations, std::vector< float > &strengths) const
const float * getSurfacePatch () const
 Getter (const) for the surface patch.
float * getSurfacePatch ()
 Getter for the surface patch.
const int & getSurfacePatchPixelSize () const
 Getter (const) for the pixel size of the surface patch (only one dimension)
int & getSurfacePatchPixelSize ()
 Getter for the pixel size of the surface patch (only one dimension)
const float & getSurfacePatchRotation () const
 Getter (const) for the rotation of the surface patch.
float & getSurfacePatchRotation ()
 Getter for the rotation of the surface patch.
const float & getSurfacePatchWorldSize () const
 Getter (const) for the world size of the surface patch.
float & getSurfacePatchWorldSize ()
 Getter for the world size of the surface patch.
const Eigen::Affine3f & getTransformation () const
 Getter (const) for the 6DoF pose.
Eigen::Affine3f & getTransformation ()
 Getter for the 6DoF pose.
void loadBinary (const std::string &filename)
void loadBinary (std::istream &file)
 Narf ()
 Constructor.
 Narf (const Narf &other)
 Copy Constructor.
const Narfoperator= (const Narf &other)
 Assignment operator.
void saveBinary (const std::string &filename) const
void saveBinary (std::ostream &file) const
void setDescriptor (float *descriptor)
 Setter for the descriptor.
void setSurfacePatch (float *surface_patch)
 Setter for the surface patch.
 ~Narf ()
 Destructor.

Static Public Member Functions

static void extractForEveryRangeImagePointAndAddToList (const RangeImage &range_image, int descriptor_size, float support_size, bool rotation_invariant, std::vector< Narf * > &feature_list)
static void extractForInterestPoints (const RangeImage &range_image, const PointCloud< InterestPoint > &interest_points, int descriptor_size, float support_size, bool rotation_invariant, std::vector< Narf * > &feature_list)
static void extractFromRangeImageAndAddToList (const RangeImage &range_image, const Eigen::Vector3f &interest_point, int descriptor_size, float support_size, bool rotation_invariant, std::vector< Narf * > &feature_list)
static void extractFromRangeImageAndAddToList (const RangeImage &range_image, float image_x, float image_y, int descriptor_size, float support_size, bool rotation_invariant, std::vector< Narf * > &feature_list)

Static Public Attributes

static int max_no_of_threads = 1

Protected Member Functions

void deepCopy (const Narf &other)
 Create a deep copy of other.
float * getBlurredSurfacePatch (int new_pixel_size, int blur_radius) const
 Get the surface patch with a blur on it.
int loadHeader (std::istream &file) const
void reset ()
 Reset al members to default values and free allocated memory.
void saveHeader (std::ostream &file) const

Static Protected Member Functions

static const std::string getHeaderKeyword ()

Protected Attributes

float * descriptor_
int descriptor_size_
Eigen::Vector3f position_
float * surface_patch_
int surface_patch_pixel_size_
float surface_patch_rotation_
float surface_patch_world_size_
Eigen::Affine3f transformation_

Static Protected Attributes

static const int VERSION = 1

Detailed Description

NARF (Normal Aligned Radial Features) is a point feature descriptor type for 3D data. Please refer to pcl/features/narf_descriptor.h if you want the class derived from pcl Feature.

Author:
Bastian Steder

Definition at line 58 of file narf.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 57 of file narf.cpp.

pcl::Narf::Narf ( const Narf other)

Copy Constructor.

Definition at line 72 of file narf.cpp.

Destructor.

Definition at line 66 of file narf.cpp.


Member Function Documentation

void pcl::Narf::copyToNarf36 ( Narf36 narf36) const [inline]

Copy the descriptor and pose to the point struct Narf36.

Definition at line 51 of file narf.hpp.

void pcl::Narf::deepCopy ( const Narf other) [protected]

Create a deep copy of other.

Definition at line 104 of file narf.cpp.

bool pcl::Narf::extractDescriptor ( int  descriptor_size)

Create the descriptor from the already set other members.

Definition at line 134 of file narf.cpp.

void pcl::Narf::extractForEveryRangeImagePointAndAddToList ( const RangeImage range_image,
int  descriptor_size,
float  support_size,
bool  rotation_invariant,
std::vector< Narf * > &  feature_list 
) [static]

Extract an NARF for every point in the range image.

Definition at line 426 of file narf.cpp.

void pcl::Narf::extractForInterestPoints ( const RangeImage range_image,
const PointCloud< InterestPoint > &  interest_points,
int  descriptor_size,
float  support_size,
bool  rotation_invariant,
std::vector< Narf * > &  feature_list 
) [static]

Get a list of features from the given interest points.

!! nizar 20110408 : for OpenMP sake on MSVC this must be kept signed

Definition at line 374 of file narf.cpp.

bool pcl::Narf::extractFromRangeImage ( const RangeImage range_image,
const Eigen::Affine3f &  pose,
int  descriptor_size,
float  support_size,
int  surface_patch_world_size = NARF_DEFAULT_SURFACE_PATCH_PIXEL_SIZE 
)

Method to extract a NARF feature from a certain 3D point using a range image. pose determines the coordinate system of the feature, whereas it transforms a point from the world into the feature system. This means the interest point at which the feature is extracted will be the inverse application of pose onto (0,0,0). descriptor_size_ determines the size of the descriptor, support_size determines the support size of the feature, meaning the size in the world it covers

Definition at line 203 of file narf.cpp.

bool pcl::Narf::extractFromRangeImage ( const RangeImage range_image,
float  x,
float  y,
int  descriptor_size,
float  support_size 
)

Same as above, but determines the transformation from the surface in the range image.

Definition at line 225 of file narf.cpp.

bool pcl::Narf::extractFromRangeImage ( const RangeImage range_image,
const InterestPoint interest_point,
int  descriptor_size,
float  support_size 
)

Same as above.

Definition at line 237 of file narf.cpp.

bool pcl::Narf::extractFromRangeImage ( const RangeImage range_image,
const Eigen::Vector3f &  interest_point,
int  descriptor_size,
float  support_size 
)

Same as above.

Definition at line 244 of file narf.cpp.

void pcl::Narf::extractFromRangeImageAndAddToList ( const RangeImage range_image,
const Eigen::Vector3f &  interest_point,
int  descriptor_size,
float  support_size,
bool  rotation_invariant,
std::vector< Narf * > &  feature_list 
) [static]

Add features extracted at the given interest point and add them to the list

Definition at line 340 of file narf.cpp.

void pcl::Narf::extractFromRangeImageAndAddToList ( const RangeImage range_image,
float  image_x,
float  image_y,
int  descriptor_size,
float  support_size,
bool  rotation_invariant,
std::vector< Narf * > &  feature_list 
) [static]

Same as above

Definition at line 362 of file narf.cpp.

bool pcl::Narf::extractFromRangeImageWithBestRotation ( const RangeImage range_image,
const Eigen::Vector3f &  interest_point,
int  descriptor_size,
float  support_size 
)

Same as above, but using the rotational invariant version by choosing the best extracted rotation around the normal. Use extractFromRangeImageAndAddToList if you want to enable the system to return multiple features with different rotations.

Definition at line 253 of file narf.cpp.

void pcl::Narf::freeSurfacePatch ( ) [inline]

Method to erase the surface patch and free the memory.

Definition at line 219 of file narf.h.

float * pcl::Narf::getBlurredSurfacePatch ( int  new_pixel_size,
int  blur_radius 
) const [protected]

Get the surface patch with a blur on it.

Definition at line 278 of file narf.cpp.

const float* pcl::Narf::getDescriptor ( ) const [inline]

Getter (const) for the descriptor.

Definition at line 171 of file narf.h.

float* pcl::Narf::getDescriptor ( ) [inline]

Getter for the descriptor.

Definition at line 174 of file narf.h.

float pcl::Narf::getDescriptorDistance ( const Narf other) const [inline]

Calculate descriptor distance, value in [0,1] with 0 meaning identical and 1 every cell above maximum distance.

Definition at line 43 of file narf.hpp.

const int& pcl::Narf::getDescriptorSize ( ) const [inline]

Getter (const) for the descriptor length.

Definition at line 177 of file narf.h.

int& pcl::Narf::getDescriptorSize ( ) [inline]

Getter for the descriptor length.

Definition at line 180 of file narf.h.

static const std::string pcl::Narf::getHeaderKeyword ( ) [inline, static, protected]

Definition at line 260 of file narf.h.

int pcl::Narf::getNoOfBeamPoints ( ) const [inline]

How many points on each beam of the gradient star are used to calculate the descriptor?

Definition at line 144 of file narf.h.

const Eigen::Vector3f& pcl::Narf::getPosition ( ) const [inline]

Getter (const) for the position.

Definition at line 183 of file narf.h.

Eigen::Vector3f& pcl::Narf::getPosition ( ) [inline]

Getter for the position.

Definition at line 186 of file narf.h.

void pcl::Narf::getRotatedVersions ( const RangeImage range_image,
const std::vector< float > &  rotations,
std::vector< Narf * > &  features 
) const

Definition at line 496 of file narf.cpp.

void pcl::Narf::getRotations ( std::vector< float > &  rotations,
std::vector< float > &  strengths 
) const

Definition at line 441 of file narf.cpp.

const float* pcl::Narf::getSurfacePatch ( ) const [inline]

Getter (const) for the surface patch.

Definition at line 213 of file narf.h.

float* pcl::Narf::getSurfacePatch ( ) [inline]

Getter for the surface patch.

Definition at line 216 of file narf.h.

const int& pcl::Narf::getSurfacePatchPixelSize ( ) const [inline]

Getter (const) for the pixel size of the surface patch (only one dimension)

Definition at line 195 of file narf.h.

Getter for the pixel size of the surface patch (only one dimension)

Definition at line 198 of file narf.h.

const float& pcl::Narf::getSurfacePatchRotation ( ) const [inline]

Getter (const) for the rotation of the surface patch.

Definition at line 207 of file narf.h.

Getter for the rotation of the surface patch.

Definition at line 210 of file narf.h.

const float& pcl::Narf::getSurfacePatchWorldSize ( ) const [inline]

Getter (const) for the world size of the surface patch.

Definition at line 201 of file narf.h.

Getter for the world size of the surface patch.

Definition at line 204 of file narf.h.

const Eigen::Affine3f& pcl::Narf::getTransformation ( ) const [inline]

Getter (const) for the 6DoF pose.

Definition at line 189 of file narf.h.

Eigen::Affine3f& pcl::Narf::getTransformation ( ) [inline]

Getter for the 6DoF pose.

Definition at line 192 of file narf.h.

void pcl::Narf::loadBinary ( const std::string &  filename)

Read from file

Definition at line 596 of file narf.cpp.

void pcl::Narf::loadBinary ( std::istream &  file)

Read from input stream

Definition at line 570 of file narf.cpp.

int pcl::Narf::loadHeader ( std::istream &  file) const [protected]

Read header from input stream

Definition at line 549 of file narf.cpp.

const Narf & pcl::Narf::operator= ( const Narf other)

Assignment operator.

Definition at line 82 of file narf.cpp.

void pcl::Narf::reset ( ) [protected]

Reset al members to default values and free allocated memory.

Definition at line 90 of file narf.cpp.

void pcl::Narf::saveBinary ( const std::string &  filename) const

Write to file

Definition at line 539 of file narf.cpp.

void pcl::Narf::saveBinary ( std::ostream &  file) const

Write to output stream

Definition at line 523 of file narf.cpp.

void pcl::Narf::saveHeader ( std::ostream &  file) const [protected]

Write header to output stream

Definition at line 516 of file narf.cpp.

void pcl::Narf::setDescriptor ( float *  descriptor) [inline]

Setter for the descriptor.

Definition at line 224 of file narf.h.

void pcl::Narf::setSurfacePatch ( float *  surface_patch) [inline]

Setter for the surface patch.

Definition at line 227 of file narf.h.


Member Data Documentation

float* pcl::Narf::descriptor_ [protected]

Definition at line 272 of file narf.h.

int pcl::Narf::descriptor_size_ [protected]

Definition at line 273 of file narf.h.

int pcl::Narf::max_no_of_threads = 1 [static]

The maximum number of openmp threads that can be used in this class

Definition at line 75 of file narf.h.

Eigen::Vector3f pcl::Narf::position_ [protected]

Definition at line 266 of file narf.h.

float* pcl::Narf::surface_patch_ [protected]

Definition at line 268 of file narf.h.

Definition at line 269 of file narf.h.

Definition at line 271 of file narf.h.

Definition at line 270 of file narf.h.

Eigen::Affine3f pcl::Narf::transformation_ [protected]

Definition at line 267 of file narf.h.

const int pcl::Narf::VERSION = 1 [static, protected]

Definition at line 263 of file narf.h.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:40