Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions
cob_3d_features::OrganizedFeatures< PointInT, PointOutT > Class Template Reference

#include <organized_features.h>

Inheritance diagram for cob_3d_features::OrganizedFeatures< PointInT, PointOutT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef pcl::PointCloud< PointInT > PointCloudIn
typedef PointCloudIn::ConstPtr PointCloudInConstPtr
typedef PointCloudIn::Ptr PointCloudInPtr
typedef pcl::PointCloud
< PointOutT > 
PointCloudOut

Public Member Functions

void compute (PointCloudOut &output)
void computeMaskManually (int cloud_width)
 OrganizedFeatures ()
 Empty constructor.
int searchForNeighbors (int index, std::vector< int > &indices)
int searchForNeighborsInRange (int index, std::vector< int > &indices)
int searchForNeighborsInRange (int index, std::vector< int > &indices, std::vector< float > &sqr_distances)
void setPixelSearchRadius (int pixel_radius, int pixel_steps=1, int circle_steps=1)
void setPixelWindowSize (int size, int pixel_steps=1, int circle_steps=1)
void setSearchSurface (const PointCloudInConstPtr cloud)
void setSkipDistantPointThreshold (float th)

Protected Member Functions

virtual bool deinitCompute ()
const std::string & getClassName () const
virtual bool initCompute ()
bool isInImage (int u, int v)
bool isInRange (const PointInT &pi, const PointInT &pq, float distance_th_sqr)

Protected Attributes

int circle_steps_
bool fake_surface_
std::string feature_name_
float inv_width_
std::vector< std::vector< int > > mask_
bool mask_changed_
int n_points_
int pixel_search_radius_
int pixel_steps_
float skip_distant_point_threshold_
PointCloudInConstPtr surface_

Private Member Functions

virtual void computeFeature (PointCloudOut &output)=0

Detailed Description

template<typename PointInT, typename PointOutT>
class cob_3d_features::OrganizedFeatures< PointInT, PointOutT >

Definition at line 72 of file organized_features.h.


Member Typedef Documentation

template<typename PointInT, typename PointOutT>
typedef pcl::PointCloud<PointInT> cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::PointCloudIn
template<typename PointInT, typename PointOutT>
typedef PointCloudIn::ConstPtr cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::PointCloudInConstPtr
template<typename PointInT, typename PointOutT>
typedef PointCloudIn::Ptr cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::PointCloudInPtr
template<typename PointInT, typename PointOutT>
typedef pcl::PointCloud<PointOutT> cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::PointCloudOut

Constructor & Destructor Documentation

template<typename PointInT, typename PointOutT>
cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::OrganizedFeatures ( ) [inline]

Empty constructor.

Definition at line 87 of file organized_features.h.


Member Function Documentation

template<typename PointInT , typename PointOutT >
void cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::compute ( PointCloudOut output)

Definition at line 321 of file organized_features.hpp.

template<typename PointInT, typename PointOutT>
virtual void cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::computeFeature ( PointCloudOut output) [private, pure virtual]
template<typename PointInT , typename PointOutT >
void cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::computeMaskManually ( int  cloud_width)

Definition at line 356 of file organized_features.hpp.

template<typename PointInT , typename PointOutT >
bool cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::deinitCompute ( ) [inline, protected, virtual]

Definition at line 309 of file organized_features.hpp.

template<typename PointInT, typename PointOutT>
const std::string& cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::getClassName ( ) const [inline, protected]

Definition at line 166 of file organized_features.h.

template<typename PointInT , typename PointOutT >
bool cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::initCompute ( ) [inline, protected, virtual]

Definition at line 234 of file organized_features.hpp.

template<typename PointInT, typename PointOutT>
bool cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::isInImage ( int  u,
int  v 
) [inline, protected]

Definition at line 160 of file organized_features.h.

template<typename PointInT, typename PointOutT>
bool cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::isInRange ( const PointInT &  pi,
const PointInT &  pq,
float  distance_th_sqr 
) [inline, protected]

Definition at line 151 of file organized_features.h.

template<typename PointInT , typename PointOutT >
int cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::searchForNeighbors ( int  index,
std::vector< int > &  indices 
)

Definition at line 67 of file organized_features.hpp.

template<typename PointInT , typename PointOutT >
int cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::searchForNeighborsInRange ( int  index,
std::vector< int > &  indices 
)

Definition at line 113 of file organized_features.hpp.

template<typename PointInT , typename PointOutT >
int cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::searchForNeighborsInRange ( int  index,
std::vector< int > &  indices,
std::vector< float > &  sqr_distances 
)

Definition at line 172 of file organized_features.hpp.

template<typename PointInT, typename PointOutT>
void cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::setPixelSearchRadius ( int  pixel_radius,
int  pixel_steps = 1,
int  circle_steps = 1 
) [inline]

Definition at line 115 of file organized_features.h.

template<typename PointInT, typename PointOutT>
void cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::setPixelWindowSize ( int  size,
int  pixel_steps = 1,
int  circle_steps = 1 
) [inline]

Definition at line 106 of file organized_features.h.

template<typename PointInT, typename PointOutT>
void cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::setSearchSurface ( const PointCloudInConstPtr  cloud) [inline]

Definition at line 99 of file organized_features.h.

template<typename PointInT, typename PointOutT>
void cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::setSkipDistantPointThreshold ( float  th) [inline]

Definition at line 126 of file organized_features.h.


Member Data Documentation

template<typename PointInT, typename PointOutT>
int cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::circle_steps_ [protected]

Definition at line 172 of file organized_features.h.

template<typename PointInT, typename PointOutT>
bool cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::fake_surface_ [protected]

Definition at line 178 of file organized_features.h.

template<typename PointInT, typename PointOutT>
std::string cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::feature_name_ [protected]

Definition at line 181 of file organized_features.h.

template<typename PointInT, typename PointOutT>
float cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::inv_width_ [protected]

Definition at line 175 of file organized_features.h.

template<typename PointInT, typename PointOutT>
std::vector<std::vector<int> > cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::mask_ [protected]

Definition at line 173 of file organized_features.h.

template<typename PointInT, typename PointOutT>
bool cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::mask_changed_ [protected]

Definition at line 179 of file organized_features.h.

template<typename PointInT, typename PointOutT>
int cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::n_points_ [protected]

Definition at line 174 of file organized_features.h.

template<typename PointInT, typename PointOutT>
int cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::pixel_search_radius_ [protected]

Definition at line 170 of file organized_features.h.

template<typename PointInT, typename PointOutT>
int cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::pixel_steps_ [protected]

Definition at line 171 of file organized_features.h.

template<typename PointInT, typename PointOutT>
float cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::skip_distant_point_threshold_ [protected]

Definition at line 176 of file organized_features.h.

template<typename PointInT, typename PointOutT>
PointCloudInConstPtr cob_3d_features::OrganizedFeatures< PointInT, PointOutT >::surface_ [protected]

Definition at line 168 of file organized_features.h.


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


cob_3d_features
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:02:26