$search

vfh_recognizer_db::VFHRecognizerDB< Distance > Class Template Reference

#include <vfh_recognition.h>

Inheritance diagram for vfh_recognizer_db::VFHRecognizerDB< Distance >:
Inheritance graph
[legend]

List of all members.

Public Member Functions

bool buildCachesFromDB (bf::path dpath, int iteration)
bool buildTreeFromDB (int iteration)
int buildTreeFromViews (std::vector< boost::shared_ptr< household_objects_database::DatabaseView > > &views)
bool detect (const sensor_msgs::PointCloud2ConstPtr &msg, int nModels, std::vector< int > &model_ids, std::vector< geometry_msgs::Pose > &poses, std::vector< float > &confidences, bool use_fitness_score=true, std::vector< boost::shared_ptr< household_objects_database::DatabaseView > > *views=NULL, std::vector< std::string > *vfh_ids_vec=NULL)
 Given a cluster returns the n-most similar models in models_, their poses and the detection confidence.
bool getVFHHistogramFromVFHId (pcl::PointCloud< pcl::VFHSignature308 > &vfh_descriptor, std::string vfh_id)
bool initialize (bool useDB, bf::path dpath, int linear=0, int iteration=0, bool no_save=false)
 Initialize the data structures for recognition.
int initializeFromViews (std::vector< boost::shared_ptr< household_objects_database::DatabaseView > > &views)
bool isCacheEnabled ()
void setCacheEnabled (bool e)
 VFHRecognizerDB (bool enable_cache=false)

Public Attributes

bool cache_enabled_
std::map< int, std::vector
< float > > 
cluster_centroids_cache_
std::map< int,
geometry_msgs::Pose
pose_cache_
std::map< int, pcl::PointCloud
< pcl::VFHSignature308 >
, std::less< int >
, Eigen::aligned_allocator
< pcl::VFHSignature308 > > 
roll_cache_
std::map< int, std::string > scaled_model_id_cache_
std::map< int, pcl::PointCloud
< pcl::VFHSignature308 >
, std::less< int >
, Eigen::aligned_allocator
< pcl::VFHSignature308 > > 
vfh_cache_
std::map< int, pcl::PointCloud
< pcl::PointNormal >
, std::less< int >
, Eigen::aligned_allocator
< pcl::PointNormal > > 
view_cache_

Private Types

typedef
vfh_recognition::VFHRecognizer
< Distance > 
base_t
typedef Distance< float > DistT

Private Member Functions

std::string getModelId (std::string id)
bool getPointCloudFromId (pcl::PointCloud< pcl::PointNormal > &cloud, std::string id)
bool getPoseFromId (std::string id, geometry_msgs::Pose &pose)
bool getVFHCentroidFromVFHid (std::vector< float > &centroid, std::string id)
int getVFHId (std::string id)
bool getVFHRollOrientationFromId (pcl::PointCloud< pcl::VFHSignature308 > &vfh_orientation_signature, std::string id)
bool getVFHRollOrientationFromIdThroughView (pcl::PointCloud< pcl::VFHSignature308 > &vfh_orientation_signature, std::string id)
bool getViewCentroidFromVFHid (std::vector< float > &centroid, std::string id)

Private Attributes

household_objects_database::ObjectsDatabasedatabase

Detailed Description

template<template< class > class Distance>
class vfh_recognizer_db::VFHRecognizerDB< Distance >

Definition at line 17 of file vfh_recognition.h.


Member Typedef Documentation

template<template< class > class Distance>
typedef vfh_recognition::VFHRecognizer<Distance> vfh_recognizer_db::VFHRecognizerDB< Distance >::base_t [private]

Definition at line 19 of file vfh_recognition.h.

template<template< class > class Distance>
typedef Distance<float> vfh_recognizer_db::VFHRecognizerDB< Distance >::DistT [private]

Reimplemented from vfh_recognition::VFHRecognizer< Distance >.

Definition at line 24 of file vfh_recognition.h.


Constructor & Destructor Documentation

template<template< class > class Distance>
vfh_recognizer_db::VFHRecognizerDB< Distance >::VFHRecognizerDB ( bool  enable_cache = false  )  [inline]

Definition at line 27 of file vfh_recognition.h.


Member Function Documentation

template<template< class > class Distance>
bool vfh_recognizer_db::VFHRecognizerDB< Distance >::buildCachesFromDB ( bf::path  dpath,
int  iteration 
) [inline]

Definition at line 500 of file vfh_recognition.cpp.

template<template< class > class Distance>
bool vfh_recognizer_db::VFHRecognizerDB< Distance >::buildTreeFromDB ( int  iteration  )  [inline]

Definition at line 446 of file vfh_recognition.cpp.

template<template< class > class Distance>
int vfh_recognizer_db::VFHRecognizerDB< Distance >::buildTreeFromViews ( std::vector< boost::shared_ptr< household_objects_database::DatabaseView > > &  views  )  [inline]

Definition at line 387 of file vfh_recognition.cpp.

template<template< class > class Distance>
bool vfh_recognizer_db::VFHRecognizerDB< Distance >::detect ( const sensor_msgs::PointCloud2ConstPtr msg,
int  nModels,
std::vector< int > &  model_ids,
std::vector< geometry_msgs::Pose > &  poses,
std::vector< float > &  confidences,
bool  use_fitness_score = true,
std::vector< boost::shared_ptr< household_objects_database::DatabaseView > > *  views = NULL,
std::vector< std::string > *  vfh_ids_vec = NULL 
) [inline]

Given a cluster returns the n-most similar models in models_, their poses and the detection confidence.

Definition at line 350 of file vfh_recognition.cpp.

template<template< class > class Distance>
std::string vfh_recognizer_db::VFHRecognizerDB< Distance >::getModelId ( std::string  id  )  [inline, private, virtual]

Implements vfh_recognition::VFHRecognizer< Distance >.

Definition at line 201 of file vfh_recognition.cpp.

template<template< class > class Distance>
bool vfh_recognizer_db::VFHRecognizerDB< Distance >::getPointCloudFromId ( pcl::PointCloud< pcl::PointNormal > &  cloud,
std::string  id 
) [inline, private, virtual]

Implements vfh_recognition::VFHRecognizer< Distance >.

Definition at line 9 of file vfh_recognition.cpp.

template<template< class > class Distance>
bool vfh_recognizer_db::VFHRecognizerDB< Distance >::getPoseFromId ( std::string  id,
geometry_msgs::Pose pose 
) [inline, private, virtual]

Implements vfh_recognition::VFHRecognizer< Distance >.

Definition at line 180 of file vfh_recognition.cpp.

template<template< class > class Distance>
bool vfh_recognizer_db::VFHRecognizerDB< Distance >::getVFHCentroidFromVFHid ( std::vector< float > &  centroid,
std::string  id 
) [inline, private, virtual]

Implements vfh_recognition::VFHRecognizer< Distance >.

Definition at line 73 of file vfh_recognition.cpp.

template<template< class > class Distance>
bool vfh_recognizer_db::VFHRecognizerDB< Distance >::getVFHHistogramFromVFHId ( pcl::PointCloud< pcl::VFHSignature308 > &  vfh_descriptor,
std::string  vfh_id 
) [inline, virtual]

Implements vfh_recognition::VFHRecognizer< Distance >.

Definition at line 37 of file vfh_recognition.cpp.

template<template< class > class Distance>
int vfh_recognizer_db::VFHRecognizerDB< Distance >::getVFHId ( std::string  id  )  [inline, private, virtual]

Implements vfh_recognition::VFHRecognizer< Distance >.

Definition at line 172 of file vfh_recognition.cpp.

template<template< class > class Distance>
bool vfh_recognizer_db::VFHRecognizerDB< Distance >::getVFHRollOrientationFromId ( pcl::PointCloud< pcl::VFHSignature308 > &  vfh_orientation_signature,
std::string  id 
) [inline, private, virtual]

Implements vfh_recognition::VFHRecognizer< Distance >.

Definition at line 112 of file vfh_recognition.cpp.

template<template< class > class Distance>
bool vfh_recognizer_db::VFHRecognizerDB< Distance >::getVFHRollOrientationFromIdThroughView ( pcl::PointCloud< pcl::VFHSignature308 > &  vfh_orientation_signature,
std::string  id 
) [inline, private, virtual]

Implements vfh_recognition::VFHRecognizer< Distance >.

Definition at line 142 of file vfh_recognition.cpp.

template<template< class > class Distance>
bool vfh_recognizer_db::VFHRecognizerDB< Distance >::getViewCentroidFromVFHid ( std::vector< float > &  centroid,
std::string  id 
) [inline, private, virtual]

Implements vfh_recognition::VFHRecognizer< Distance >.

Definition at line 99 of file vfh_recognition.cpp.

template<template< class > class Distance>
bool vfh_recognizer_db::VFHRecognizerDB< Distance >::initialize ( bool  useDB,
bf::path  dpath,
int  linear = 0,
int  iteration = 0,
bool  no_save = false 
) [inline]

Initialize the data structures for recognition.

Parameters:
useDB - if true creates the structures from the database

  • if false, uses the cached kdtree if found, otherwise builds from DB

Definition at line 233 of file vfh_recognition.cpp.

template<template< class > class Distance>
int vfh_recognizer_db::VFHRecognizerDB< Distance >::initializeFromViews ( std::vector< boost::shared_ptr< household_objects_database::DatabaseView > > &  views  )  [inline]

Definition at line 222 of file vfh_recognition.cpp.

template<template< class > class Distance>
bool vfh_recognizer_db::VFHRecognizerDB< Distance >::isCacheEnabled (  )  [inline]

Definition at line 28 of file vfh_recognition.h.

template<template< class > class Distance>
void vfh_recognizer_db::VFHRecognizerDB< Distance >::setCacheEnabled ( bool  e  )  [inline]

Definition at line 29 of file vfh_recognition.h.


Member Data Documentation

template<template< class > class Distance>
bool vfh_recognizer_db::VFHRecognizerDB< Distance >::cache_enabled_

Definition at line 91 of file vfh_recognition.h.

template<template< class > class Distance>
std::map<int, std::vector<float> > vfh_recognizer_db::VFHRecognizerDB< Distance >::cluster_centroids_cache_

Definition at line 95 of file vfh_recognition.h.

template<template< class > class Distance>
household_objects_database::ObjectsDatabase* vfh_recognizer_db::VFHRecognizerDB< Distance >::database [private]

Definition at line 33 of file vfh_recognition.h.

template<template< class > class Distance>
std::map<int, geometry_msgs::Pose > vfh_recognizer_db::VFHRecognizerDB< Distance >::pose_cache_

Definition at line 96 of file vfh_recognition.h.

template<template< class > class Distance>
std::map<int, pcl::PointCloud<pcl::VFHSignature308>, std::less<int>, Eigen::aligned_allocator<pcl::VFHSignature308> > vfh_recognizer_db::VFHRecognizerDB< Distance >::roll_cache_

Definition at line 92 of file vfh_recognition.h.

template<template< class > class Distance>
std::map<int, std::string > vfh_recognizer_db::VFHRecognizerDB< Distance >::scaled_model_id_cache_

Definition at line 97 of file vfh_recognition.h.

template<template< class > class Distance>
std::map<int, pcl::PointCloud<pcl::VFHSignature308>, std::less<int>, Eigen::aligned_allocator<pcl::VFHSignature308> > vfh_recognizer_db::VFHRecognizerDB< Distance >::vfh_cache_

Definition at line 93 of file vfh_recognition.h.

template<template< class > class Distance>
std::map<int, pcl::PointCloud<pcl::PointNormal>, std::less<int>, Eigen::aligned_allocator<pcl::PointNormal> > vfh_recognizer_db::VFHRecognizerDB< Distance >::view_cache_

Definition at line 94 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


vfh_recognizer_db
Author(s): Aitor Aldoma
autogenerated on Tue Mar 5 15:26:40 2013