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. See B. Steder, R. B. Rusu, K. Konolige, and W. Burgard Point Feature Extraction on 3D Range Scans Taking into Account Object Boundaries In Proc. of the IEEE Int. Conf. on Robotics &Automation (ICRA). 2011. More...
#include <narf.h>
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 Narf & | operator= (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 |
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. See B. Steder, R. B. Rusu, K. Konolige, and W. Burgard Point Feature Extraction on 3D Range Scans Taking into Account Object Boundaries In Proc. of the IEEE Int. Conf. on Robotics &Automation (ICRA). 2011.
pcl::Narf::Narf | ( | ) |
pcl::Narf::Narf | ( | const Narf & | other | ) |
pcl::Narf::~Narf | ( | ) |
void pcl::Narf::copyToNarf36 | ( | Narf36 & | narf36 | ) | const [inline] |
void pcl::Narf::deepCopy | ( | const Narf & | other | ) | [protected] |
bool pcl::Narf::extractDescriptor | ( | int | descriptor_size | ) |
void pcl::Narf::extractForEveryRangeImagePointAndAddToList | ( | const RangeImage & | range_image, |
int | descriptor_size, | ||
float | support_size, | ||
bool | rotation_invariant, | ||
std::vector< Narf * > & | feature_list | ||
) | [static] |
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] |
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
bool pcl::Narf::extractFromRangeImage | ( | const RangeImage & | range_image, |
float | x, | ||
float | y, | ||
int | descriptor_size, | ||
float | support_size | ||
) |
bool pcl::Narf::extractFromRangeImage | ( | const RangeImage & | range_image, |
const InterestPoint & | interest_point, | ||
int | descriptor_size, | ||
float | support_size | ||
) |
bool pcl::Narf::extractFromRangeImage | ( | const RangeImage & | range_image, |
const Eigen::Vector3f & | interest_point, | ||
int | descriptor_size, | ||
float | support_size | ||
) |
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] |
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] |
bool pcl::Narf::extractFromRangeImageWithBestRotation | ( | const RangeImage & | range_image, |
const Eigen::Vector3f & | interest_point, | ||
int | descriptor_size, | ||
float | support_size | ||
) |
void pcl::Narf::freeSurfacePatch | ( | ) | [inline] |
float * pcl::Narf::getBlurredSurfacePatch | ( | int | new_pixel_size, |
int | blur_radius | ||
) | const [protected] |
const float* pcl::Narf::getDescriptor | ( | ) | const [inline] |
float* pcl::Narf::getDescriptor | ( | ) | [inline] |
float pcl::Narf::getDescriptorDistance | ( | const Narf & | other | ) | const [inline] |
const int& pcl::Narf::getDescriptorSize | ( | ) | const [inline] |
int& pcl::Narf::getDescriptorSize | ( | ) | [inline] |
static const std::string pcl::Narf::getHeaderKeyword | ( | ) | [inline, static, protected] |
int pcl::Narf::getNoOfBeamPoints | ( | ) | const [inline] |
const Eigen::Vector3f& pcl::Narf::getPosition | ( | ) | const [inline] |
Eigen::Vector3f& pcl::Narf::getPosition | ( | ) | [inline] |
void pcl::Narf::getRotatedVersions | ( | const RangeImage & | range_image, |
const std::vector< float > & | rotations, | ||
std::vector< Narf * > & | features | ||
) | const |
void pcl::Narf::getRotations | ( | std::vector< float > & | rotations, |
std::vector< float > & | strengths | ||
) | const |
const float* pcl::Narf::getSurfacePatch | ( | ) | const [inline] |
float* pcl::Narf::getSurfacePatch | ( | ) | [inline] |
const int& pcl::Narf::getSurfacePatchPixelSize | ( | ) | const [inline] |
int& pcl::Narf::getSurfacePatchPixelSize | ( | ) | [inline] |
const float& pcl::Narf::getSurfacePatchRotation | ( | ) | const [inline] |
float& pcl::Narf::getSurfacePatchRotation | ( | ) | [inline] |
const float& pcl::Narf::getSurfacePatchWorldSize | ( | ) | const [inline] |
float& pcl::Narf::getSurfacePatchWorldSize | ( | ) | [inline] |
const Eigen::Affine3f& pcl::Narf::getTransformation | ( | ) | const [inline] |
Eigen::Affine3f& pcl::Narf::getTransformation | ( | ) | [inline] |
void pcl::Narf::loadBinary | ( | const std::string & | filename | ) |
void pcl::Narf::loadBinary | ( | std::istream & | file | ) |
int pcl::Narf::loadHeader | ( | std::istream & | file | ) | const [protected] |
void pcl::Narf::reset | ( | ) | [protected] |
void pcl::Narf::saveBinary | ( | const std::string & | filename | ) | const |
void pcl::Narf::saveBinary | ( | std::ostream & | file | ) | const |
void pcl::Narf::saveHeader | ( | std::ostream & | file | ) | const [protected] |
void pcl::Narf::setDescriptor | ( | float * | descriptor | ) | [inline] |
void pcl::Narf::setSurfacePatch | ( | float * | surface_patch | ) | [inline] |
float* pcl::Narf::descriptor_ [protected] |
int pcl::Narf::descriptor_size_ [protected] |
int pcl::Narf::max_no_of_threads = 1 [static] |
Eigen::Vector3f pcl::Narf::position_ [protected] |
float* pcl::Narf::surface_patch_ [protected] |
int pcl::Narf::surface_patch_pixel_size_ [protected] |
float pcl::Narf::surface_patch_rotation_ [protected] |
float pcl::Narf::surface_patch_world_size_ [protected] |
Eigen::Affine3f pcl::Narf::transformation_ [protected] |
const int pcl::Narf::VERSION = 1 [static, protected] |