$search

vfh_recognition::VFHRecognizer< Distance > Class Template Reference

#include <vfh_recognition.h>

List of all members.

Public Member Functions

int computeAngleRollOrientationFrequency (cv::Mat &hist_fft, cv::Mat &hist_fft_input, int nr_bins_, Eigen::Vector4f centroid_view, Eigen::Vector4f centroid_input, const pcl::PointCloud< pcl::PointNormal > &view, const pcl::PointCloud< pcl::PointNormal > &input, int jj, pcl::PointCloud< pcl::VFHSignature308 > &hist_view, pcl::PointCloud< pcl::VFHSignature308 > &hist_input)
bool computeNormals (pcl::PointCloud< pcl::PointXYZ >::Ptr input, pcl::PointCloud< pcl::PointNormal >::Ptr cloud_normals)
bool computeVFH (pcl::PointCloud< pcl::PointXYZ >::Ptr input, pcl::PointCloud< pcl::PointNormal >::Ptr cloud_normals, std::vector< pcl::PointCloud< pcl::VFHSignature308 >, Eigen::aligned_allocator< pcl::PointCloud< pcl::VFHSignature308 > > > &vfh_signatures, std::vector< Eigen::Vector3f > &centroids_dominant_orientations)
void computeVFHRollOrientation (pcl::PointCloud< pcl::PointNormal >::Ptr input, pcl::PointCloud< pcl::VFHSignature308 >::Ptr vfh_signature, Eigen::Vector3f &centroid, cv::Mat &frequency_domain)
bool detect_ (const sensor_msgs::PointCloud2ConstPtr &msg, int nModels, std::vector< std::string > &model_ids, std::vector< geometry_msgs::Pose > &poses, std::vector< float > &confidences, std::vector< std::string > &vfh_ids, bool use_fitness_score=true)
void getCentroids (std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > *centroids)
void getCentroidsResults (std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > *centroids)
void getICPTransformations (std::vector< Eigen::Matrix4f, Eigen::aligned_allocator< Eigen::Matrix4f > > *icp_transformations)
void getRollRotationAngles (std::vector< int > *roll_angles)
virtual bool getVFHHistogramFromVFHId (pcl::PointCloud< pcl::VFHSignature308 > &vfh_descriptor, std::string vfh_id)=0
void setApplyICP (bool apply)
void setApplyRadiusRemoval (bool apply)
void setApplyVoxelGrid (bool apply)
void setICPIterations (int iter)
void setNormalizeVFHBins (bool normalize)
void setUseClusterCentroids (bool use)
void setUseOldVFH (bool use)
 VFHRecognizer ()
 ~VFHRecognizer ()

Public Attributes

bool fill_size_component_
std::vector< float > fitness_scores_
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
pcl::PointCloud
< pcl::PointNormal > 
input_filtered
std::vector< float > roll_histogram_errors_
std::vector< float > roll_histogram_errors_flipped_
pcl::PointCloud
< pcl::VFHSignature308 > 
vfh_histogram_processed
int view_id_being_processed_

Protected Member Functions

void computeRollTransform (Eigen::Vector4f &centroidInput, Eigen::Vector4f &centroidResult, double roll_angle, Eigen::Affine3f &final_trans)
void computeTransformToZAxes (Eigen::Vector4f &centroid, Eigen::Affine3f &transform)
void filterNormalsWithHighCurvature (pcl::PointCloud< pcl::PointNormal > &cloud, std::vector< int > &indices_out, std::vector< int > &indices_in, float threshold)
virtual std::string getModelId (std::string id)=0
virtual bool getPointCloudFromId (pcl::PointCloud< pcl::PointNormal > &cloud, std::string id)=0
virtual bool getPoseFromId (std::string id, geometry_msgs::Pose &pose)=0
virtual bool getVFHCentroidFromVFHid (std::vector< float > &centroid, std::string id)=0
virtual int getVFHId (std::string id)=0
virtual bool getVFHRollOrientationFromId (pcl::PointCloud< pcl::VFHSignature308 > &vfh_orientation_signature, std::string id)=0
virtual bool getVFHRollOrientationFromIdThroughView (pcl::PointCloud< pcl::VFHSignature308 > &vfh_orientation_signature, std::string id)=0
virtual bool getViewCentroidFromVFHid (std::vector< float > &centroid, std::string id)=0
bool loadFileList (std::vector< vfh_model_db > &models, const std::string &filename)
void nearestKSearch (flann::Index< DistT > *index, const vfh_model_db &model, int k, flann::Matrix< int > &indices, flann::Matrix< float > &distances)
void saveFileList (const std::vector< vfh_model_db > &models, const std::string &filename)
 Save the list of file models.

Protected Attributes

bool apply_radius_removal_
bool apply_voxel_grid_
std::vector< Eigen::Vector4f,
Eigen::aligned_allocator
< Eigen::Vector4f > > 
centroid_inputs_
std::vector< Eigen::Vector4f,
Eigen::aligned_allocator
< Eigen::Vector4f > > 
centroid_results_
flann::Matrix< float > data_
int icp_iterations_
std::vector< Eigen::Matrix4f,
Eigen::aligned_allocator
< Eigen::Matrix4f > > 
icp_transformations_
flann::Index< DistT > * index_
int knn_
std::vector< vfh_model_dbmodels_
bool normalize_vfh_bins_
bool perform_icp_
std::vector< int > roll_rotation_angles_
bool use_cluster_centroids_
bool use_old_vfh_

Private Types

typedef Distance< float > DistT

Detailed Description

template<template< class > class Distance>
class vfh_recognition::VFHRecognizer< Distance >

Definition at line 61 of file vfh_recognition.h.


Member Typedef Documentation

template<template< class > class Distance>
typedef Distance<float> vfh_recognition::VFHRecognizer< Distance >::DistT [private]

Definition at line 64 of file vfh_recognition.h.


Constructor & Destructor Documentation

template<template< class > class Distance>
vfh_recognition::VFHRecognizer< Distance >::~VFHRecognizer (  )  [inline]

Definition at line 50 of file vfh_recognition.cpp.

template<template< class > class Distance>
vfh_recognition::VFHRecognizer< Distance >::VFHRecognizer (  )  [inline]

Definition at line 35 of file vfh_recognition.cpp.


Member Function Documentation

template<template< class > class Distance>
int vfh_recognition::VFHRecognizer< Distance >::computeAngleRollOrientationFrequency ( cv::Mat &  hist_fft,
cv::Mat &  hist_fft_input,
int  nr_bins_,
Eigen::Vector4f  centroid_view,
Eigen::Vector4f  centroid_input,
const pcl::PointCloud< pcl::PointNormal > &  view,
const pcl::PointCloud< pcl::PointNormal > &  input,
int  jj,
pcl::PointCloud< pcl::VFHSignature308 > &  hist_view,
pcl::PointCloud< pcl::VFHSignature308 > &  hist_input 
) [inline]

Definition at line 429 of file vfh_recognition.cpp.

template<template< class > class Distance>
bool vfh_recognition::VFHRecognizer< Distance >::computeNormals ( pcl::PointCloud< pcl::PointXYZ >::Ptr  input,
pcl::PointCloud< pcl::PointNormal >::Ptr  cloud_normals 
) [inline]

Definition at line 184 of file vfh_recognition.cpp.

template<template< class > class Distance>
void vfh_recognition::VFHRecognizer< Distance >::computeRollTransform ( Eigen::Vector4f &  centroidInput,
Eigen::Vector4f &  centroidResult,
double  roll_angle,
Eigen::Affine3f &  final_trans 
) [inline, protected]

Definition at line 604 of file vfh_recognition.cpp.

template<template< class > class Distance>
void vfh_recognition::VFHRecognizer< Distance >::computeTransformToZAxes ( Eigen::Vector4f &  centroid,
Eigen::Affine3f &  transform 
) [inline, protected]

Definition at line 588 of file vfh_recognition.cpp.

template<template< class > class Distance>
bool vfh_recognition::VFHRecognizer< Distance >::computeVFH ( pcl::PointCloud< pcl::PointXYZ >::Ptr  input,
pcl::PointCloud< pcl::PointNormal >::Ptr  cloud_normals,
std::vector< pcl::PointCloud< pcl::VFHSignature308 >, Eigen::aligned_allocator< pcl::PointCloud< pcl::VFHSignature308 > > > &  vfh_signatures,
std::vector< Eigen::Vector3f > &  centroids_dominant_orientations 
) [inline]

Definition at line 257 of file vfh_recognition.cpp.

template<template< class > class Distance>
void vfh_recognition::VFHRecognizer< Distance >::computeVFHRollOrientation ( pcl::PointCloud< pcl::PointNormal >::Ptr  input,
pcl::PointCloud< pcl::VFHSignature308 >::Ptr  vfh_signature,
Eigen::Vector3f &  centroid,
cv::Mat &  frequency_domain 
) [inline]

Definition at line 59 of file vfh_recognition.cpp.

template<template< class > class Distance>
bool vfh_recognition::VFHRecognizer< Distance >::detect_ ( const sensor_msgs::PointCloud2ConstPtr msg,
int  nModels,
std::vector< std::string > &  model_ids,
std::vector< geometry_msgs::Pose > &  poses,
std::vector< float > &  confidences,
std::vector< std::string > &  vfh_ids,
bool  use_fitness_score = true 
) [inline]

Definition at line 622 of file vfh_recognition.cpp.

template<template< class > class Distance>
void vfh_recognition::VFHRecognizer< Distance >::filterNormalsWithHighCurvature ( pcl::PointCloud< pcl::PointNormal > &  cloud,
std::vector< int > &  indices_out,
std::vector< int > &  indices_in,
float  threshold 
) [inline, protected]

Definition at line 154 of file vfh_recognition.cpp.

template<template< class > class Distance>
void vfh_recognition::VFHRecognizer< Distance >::getCentroids ( std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > *  centroids  )  [inline]

Definition at line 409 of file vfh_recognition.cpp.

template<template< class > class Distance>
void vfh_recognition::VFHRecognizer< Distance >::getCentroidsResults ( std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > *  centroids  )  [inline]

Definition at line 419 of file vfh_recognition.cpp.

template<template< class > class Distance>
void vfh_recognition::VFHRecognizer< Distance >::getICPTransformations ( std::vector< Eigen::Matrix4f, Eigen::aligned_allocator< Eigen::Matrix4f > > *  icp_transformations  )  [inline]

Definition at line 399 of file vfh_recognition.cpp.

template<template< class > class Distance>
virtual std::string vfh_recognition::VFHRecognizer< Distance >::getModelId ( std::string  id  )  [protected, pure virtual]
template<template< class > class Distance>
virtual bool vfh_recognition::VFHRecognizer< Distance >::getPointCloudFromId ( pcl::PointCloud< pcl::PointNormal > &  cloud,
std::string  id 
) [protected, pure virtual]
template<template< class > class Distance>
virtual bool vfh_recognition::VFHRecognizer< Distance >::getPoseFromId ( std::string  id,
geometry_msgs::Pose pose 
) [protected, pure virtual]
template<template< class > class Distance>
void vfh_recognition::VFHRecognizer< Distance >::getRollRotationAngles ( std::vector< int > *  roll_angles  )  [inline]

Definition at line 389 of file vfh_recognition.cpp.

template<template< class > class Distance>
virtual bool vfh_recognition::VFHRecognizer< Distance >::getVFHCentroidFromVFHid ( std::vector< float > &  centroid,
std::string  id 
) [protected, pure virtual]
template<template< class > class Distance>
virtual bool vfh_recognition::VFHRecognizer< Distance >::getVFHHistogramFromVFHId ( pcl::PointCloud< pcl::VFHSignature308 > &  vfh_descriptor,
std::string  vfh_id 
) [pure virtual]
template<template< class > class Distance>
virtual int vfh_recognition::VFHRecognizer< Distance >::getVFHId ( std::string  id  )  [protected, pure virtual]
template<template< class > class Distance>
virtual bool vfh_recognition::VFHRecognizer< Distance >::getVFHRollOrientationFromId ( pcl::PointCloud< pcl::VFHSignature308 > &  vfh_orientation_signature,
std::string  id 
) [protected, pure virtual]
template<template< class > class Distance>
virtual bool vfh_recognition::VFHRecognizer< Distance >::getVFHRollOrientationFromIdThroughView ( pcl::PointCloud< pcl::VFHSignature308 > &  vfh_orientation_signature,
std::string  id 
) [protected, pure virtual]
template<template< class > class Distance>
virtual bool vfh_recognition::VFHRecognizer< Distance >::getViewCentroidFromVFHid ( std::vector< float > &  centroid,
std::string  id 
) [protected, pure virtual]
template<template< class > class Distance>
bool vfh_recognition::VFHRecognizer< Distance >::loadFileList ( std::vector< vfh_model_db > &  models,
const std::string &  filename 
) [inline, protected]

Definition at line 341 of file vfh_recognition.cpp.

template<template< class > class Distance>
void vfh_recognition::VFHRecognizer< Distance >::nearestKSearch ( flann::Index< DistT > *  index,
const vfh_model_db model,
int  k,
flann::Matrix< int > &  indices,
flann::Matrix< float > &  distances 
) [inline, protected]

Definition at line 375 of file vfh_recognition.cpp.

template<template< class > class Distance>
void vfh_recognition::VFHRecognizer< Distance >::saveFileList ( const std::vector< vfh_model_db > &  models,
const std::string &  filename 
) [inline, protected]

Save the list of file models.

Parameters:
models the list models
filename the output file name

Definition at line 364 of file vfh_recognition.cpp.

template<template< class > class Distance>
void vfh_recognition::VFHRecognizer< Distance >::setApplyICP ( bool  apply  )  [inline]

Definition at line 197 of file vfh_recognition.h.

template<template< class > class Distance>
void vfh_recognition::VFHRecognizer< Distance >::setApplyRadiusRemoval ( bool  apply  )  [inline]

Definition at line 192 of file vfh_recognition.h.

template<template< class > class Distance>
void vfh_recognition::VFHRecognizer< Distance >::setApplyVoxelGrid ( bool  apply  )  [inline]

Definition at line 187 of file vfh_recognition.h.

template<template< class > class Distance>
void vfh_recognition::VFHRecognizer< Distance >::setICPIterations ( int  iter  )  [inline]

Definition at line 202 of file vfh_recognition.h.

template<template< class > class Distance>
void vfh_recognition::VFHRecognizer< Distance >::setNormalizeVFHBins ( bool  normalize  )  [inline]

Definition at line 210 of file vfh_recognition.h.

template<template< class > class Distance>
void vfh_recognition::VFHRecognizer< Distance >::setUseClusterCentroids ( bool  use  )  [inline]

Definition at line 214 of file vfh_recognition.h.

template<template< class > class Distance>
void vfh_recognition::VFHRecognizer< Distance >::setUseOldVFH ( bool  use  )  [inline]

Definition at line 206 of file vfh_recognition.h.


Member Data Documentation

template<template< class > class Distance>
bool vfh_recognition::VFHRecognizer< Distance >::apply_radius_removal_ [protected]

Definition at line 82 of file vfh_recognition.h.

template<template< class > class Distance>
bool vfh_recognition::VFHRecognizer< Distance >::apply_voxel_grid_ [protected]

Definition at line 81 of file vfh_recognition.h.

template<template< class > class Distance>
std::vector<Eigen::Vector4f,Eigen::aligned_allocator< Eigen::Vector4f > > vfh_recognition::VFHRecognizer< Distance >::centroid_inputs_ [protected]

Definition at line 74 of file vfh_recognition.h.

template<template< class > class Distance>
std::vector<Eigen::Vector4f,Eigen::aligned_allocator< Eigen::Vector4f > > vfh_recognition::VFHRecognizer< Distance >::centroid_results_ [protected]

Definition at line 73 of file vfh_recognition.h.

template<template< class > class Distance>
flann::Matrix<float> vfh_recognition::VFHRecognizer< Distance >::data_ [protected]

Definition at line 68 of file vfh_recognition.h.

template<template< class > class Distance>
bool vfh_recognition::VFHRecognizer< Distance >::fill_size_component_

Definition at line 145 of file vfh_recognition.h.

template<template< class > class Distance>
std::vector< float > vfh_recognition::VFHRecognizer< Distance >::fitness_scores_

Definition at line 144 of file vfh_recognition.h.

template<template< class > class Distance>
int vfh_recognition::VFHRecognizer< Distance >::icp_iterations_ [protected]

Definition at line 84 of file vfh_recognition.h.

template<template< class > class Distance>
std::vector<Eigen::Matrix4f,Eigen::aligned_allocator< Eigen::Matrix4f > > vfh_recognition::VFHRecognizer< Distance >::icp_transformations_ [protected]

Definition at line 75 of file vfh_recognition.h.

template<template< class > class Distance>
flann::Index<DistT>* vfh_recognition::VFHRecognizer< Distance >::index_ [protected]

Definition at line 70 of file vfh_recognition.h.

template<template< class > class Distance>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW pcl::PointCloud<pcl::PointNormal> vfh_recognition::VFHRecognizer< Distance >::input_filtered

Definition at line 139 of file vfh_recognition.h.

template<template< class > class Distance>
int vfh_recognition::VFHRecognizer< Distance >::knn_ [protected]

Definition at line 69 of file vfh_recognition.h.

template<template< class > class Distance>
std::vector<vfh_model_db> vfh_recognition::VFHRecognizer< Distance >::models_ [protected]

Definition at line 67 of file vfh_recognition.h.

template<template< class > class Distance>
bool vfh_recognition::VFHRecognizer< Distance >::normalize_vfh_bins_ [protected]

Definition at line 86 of file vfh_recognition.h.

template<template< class > class Distance>
bool vfh_recognition::VFHRecognizer< Distance >::perform_icp_ [protected]

Definition at line 83 of file vfh_recognition.h.

template<template< class > class Distance>
std::vector<float> vfh_recognition::VFHRecognizer< Distance >::roll_histogram_errors_

Definition at line 142 of file vfh_recognition.h.

template<template< class > class Distance>
std::vector<float> vfh_recognition::VFHRecognizer< Distance >::roll_histogram_errors_flipped_

Definition at line 143 of file vfh_recognition.h.

template<template< class > class Distance>
std::vector<int> vfh_recognition::VFHRecognizer< Distance >::roll_rotation_angles_ [protected]

Definition at line 71 of file vfh_recognition.h.

template<template< class > class Distance>
bool vfh_recognition::VFHRecognizer< Distance >::use_cluster_centroids_ [protected]

Definition at line 87 of file vfh_recognition.h.

template<template< class > class Distance>
bool vfh_recognition::VFHRecognizer< Distance >::use_old_vfh_ [protected]

Definition at line 85 of file vfh_recognition.h.

template<template< class > class Distance>
pcl::PointCloud<pcl::VFHSignature308> vfh_recognition::VFHRecognizer< Distance >::vfh_histogram_processed

Definition at line 140 of file vfh_recognition.h.

template<template< class > class Distance>
int vfh_recognition::VFHRecognizer< Distance >::view_id_being_processed_

Definition at line 141 of file vfh_recognition.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


vfh_recognition
Author(s): Aitor Aldoma
autogenerated on Tue Mar 5 15:13:33 2013