Public Types | Public Member Functions | Public Attributes
OpenNISegmentTracking< PointType > Class Template Reference

List of all members.

Public Types

typedef pcl::PointCloud
< PointType
Cloud
typedef Cloud::ConstPtr CloudConstPtr
typedef Cloud::Ptr CloudPtr
typedef
ParticleFilter::CoherencePtr 
CoherencePtr
typedef pcl::search::KdTree
< PointType
KdTree
typedef KdTree::Ptr KdTreePtr
typedef ParticleFilterTracker
< RefPointType, ParticleT
ParticleFilter
typedef ParticleXYZRPY ParticleT
typedef pcl::PointCloud
< RefPointType
RefCloud
typedef RefCloud::ConstPtr RefCloudConstPtr
typedef RefCloud::Ptr RefCloudPtr
typedef pcl::PointXYZRGBA RefPointType

Public Member Functions

void addNormalToCloud (const CloudConstPtr &cloud, const pcl::PointCloud< pcl::Normal >::ConstPtr &normals, RefCloud &result)
void cloud_cb (const CloudConstPtr &cloud)
void convexHull (const CloudConstPtr &cloud, Cloud &, std::vector< pcl::Vertices > &hull_vertices)
bool drawParticles (pcl::visualization::PCLVisualizer &viz)
void drawResult (pcl::visualization::PCLVisualizer &viz)
void euclideanSegment (const CloudConstPtr &cloud, std::vector< pcl::PointIndices > &cluster_indices)
void extractNonPlanePoints (const CloudConstPtr &cloud, const CloudConstPtr &cloud_hull, Cloud &result)
void extractSegmentCluster (const CloudConstPtr &cloud, const std::vector< pcl::PointIndices > cluster_indices, const int segment_index, Cloud &result)
void filterPassThrough (const CloudConstPtr &cloud, Cloud &result)
void gridSample (const CloudConstPtr &cloud, Cloud &result, double leaf_size=0.01)
void gridSampleApprox (const CloudConstPtr &cloud, Cloud &result, double leaf_size=0.01)
void normalEstimation (const CloudConstPtr &cloud, pcl::PointCloud< pcl::Normal > &result)
 OpenNISegmentTracking (const std::string &device_id, int thread_nr, double downsampling_grid_size, bool use_convex_hull, bool visualize_non_downsample, bool visualize_particles, bool use_fixed)
void planeProjection (const CloudConstPtr &cloud, Cloud &result, const pcl::ModelCoefficients::ConstPtr &coefficients)
void planeSegmentation (const CloudConstPtr &cloud, pcl::ModelCoefficients &coefficients, pcl::PointIndices &inliers)
void removeZeroPoints (const CloudConstPtr &cloud, Cloud &result)
void run ()
void tracking (const RefCloudConstPtr &cloud)
void viz_cb (pcl::visualization::PCLVisualizer &viz)

Public Attributes

CloudPtr cloud_hull_
CloudPtr cloud_pass_
CloudPtr cloud_pass_downsampled_
double computation_time_
int counter_
std::string device_id_
double downsampling_grid_size_
double downsampling_time_
std::vector< pcl::Vertices > hull_vertices_
boost::mutex mtx_
pcl::NormalEstimationOMP
< PointType, pcl::Normal
ne_
bool new_cloud_
CloudPtr nonplane_cloud_
pcl::PointCloud< pcl::Normal >::Ptr normals_
CloudPtr plane_cloud_
CloudPtr reference_
CloudPtr segmented_cloud_
boost::shared_ptr< ParticleFiltertracker_
double tracking_time_
bool use_convex_hull_
pcl::visualization::CloudViewer viewer_
bool visualize_non_downsample_
bool visualize_particles_

Detailed Description

template<typename PointType>
class OpenNISegmentTracking< PointType >

Definition at line 73 of file openni_tracking.cpp.


Member Typedef Documentation

template<typename PointType>
typedef pcl::PointCloud<PointType> OpenNISegmentTracking< PointType >::Cloud

Definition at line 81 of file openni_tracking.cpp.

template<typename PointType>
typedef Cloud::ConstPtr OpenNISegmentTracking< PointType >::CloudConstPtr

Definition at line 86 of file openni_tracking.cpp.

template<typename PointType>
typedef Cloud::Ptr OpenNISegmentTracking< PointType >::CloudPtr

Definition at line 85 of file openni_tracking.cpp.

Definition at line 91 of file openni_tracking.cpp.

template<typename PointType>
typedef pcl::search::KdTree<PointType> OpenNISegmentTracking< PointType >::KdTree

Definition at line 92 of file openni_tracking.cpp.

template<typename PointType>
typedef KdTree::Ptr OpenNISegmentTracking< PointType >::KdTreePtr

Definition at line 93 of file openni_tracking.cpp.

Definition at line 90 of file openni_tracking.cpp.

template<typename PointType>
typedef ParticleXYZRPY OpenNISegmentTracking< PointType >::ParticleT

Definition at line 79 of file openni_tracking.cpp.

template<typename PointType>
typedef pcl::PointCloud<RefPointType> OpenNISegmentTracking< PointType >::RefCloud

Definition at line 82 of file openni_tracking.cpp.

template<typename PointType>
typedef RefCloud::ConstPtr OpenNISegmentTracking< PointType >::RefCloudConstPtr

Definition at line 84 of file openni_tracking.cpp.

template<typename PointType>
typedef RefCloud::Ptr OpenNISegmentTracking< PointType >::RefCloudPtr

Definition at line 83 of file openni_tracking.cpp.

template<typename PointType>
typedef pcl::PointXYZRGBA OpenNISegmentTracking< PointType >::RefPointType

Definition at line 77 of file openni_tracking.cpp.


Constructor & Destructor Documentation

template<typename PointType>
OpenNISegmentTracking< PointType >::OpenNISegmentTracking ( const std::string &  device_id,
int  thread_nr,
double  downsampling_grid_size,
bool  use_convex_hull,
bool  visualize_non_downsample,
bool  visualize_particles,
bool  use_fixed 
) [inline]

Definition at line 94 of file openni_tracking.cpp.


Member Function Documentation

template<typename PointType>
void OpenNISegmentTracking< PointType >::addNormalToCloud ( const CloudConstPtr cloud,
const pcl::PointCloud< pcl::Normal >::ConstPtr &  normals,
RefCloud result 
) [inline]

Definition at line 415 of file openni_tracking.cpp.

template<typename PointType>
void OpenNISegmentTracking< PointType >::cloud_cb ( const CloudConstPtr cloud) [inline]

Definition at line 492 of file openni_tracking.cpp.

template<typename PointType>
void OpenNISegmentTracking< PointType >::convexHull ( const CloudConstPtr cloud,
Cloud ,
std::vector< pcl::Vertices > &  hull_vertices 
) [inline]

Definition at line 384 of file openni_tracking.cpp.

template<typename PointType>
bool OpenNISegmentTracking< PointType >::drawParticles ( pcl::visualization::PCLVisualizer viz) [inline]

Definition at line 176 of file openni_tracking.cpp.

template<typename PointType>
void OpenNISegmentTracking< PointType >::drawResult ( pcl::visualization::PCLVisualizer viz) [inline]

Definition at line 210 of file openni_tracking.cpp.

template<typename PointType>
void OpenNISegmentTracking< PointType >::euclideanSegment ( const CloudConstPtr cloud,
std::vector< pcl::PointIndices > &  cluster_indices 
) [inline]

Definition at line 308 of file openni_tracking.cpp.

template<typename PointType>
void OpenNISegmentTracking< PointType >::extractNonPlanePoints ( const CloudConstPtr cloud,
const CloudConstPtr cloud_hull,
Cloud result 
) [inline]

Definition at line 436 of file openni_tracking.cpp.

template<typename PointType>
void OpenNISegmentTracking< PointType >::extractSegmentCluster ( const CloudConstPtr cloud,
const std::vector< pcl::PointIndices >  cluster_indices,
const int  segment_index,
Cloud result 
) [inline]

Definition at line 475 of file openni_tracking.cpp.

template<typename PointType>
void OpenNISegmentTracking< PointType >::filterPassThrough ( const CloudConstPtr cloud,
Cloud result 
) [inline]

Definition at line 294 of file openni_tracking.cpp.

template<typename PointType>
void OpenNISegmentTracking< PointType >::gridSample ( const CloudConstPtr cloud,
Cloud result,
double  leaf_size = 0.01 
) [inline]

Definition at line 325 of file openni_tracking.cpp.

template<typename PointType>
void OpenNISegmentTracking< PointType >::gridSampleApprox ( const CloudConstPtr cloud,
Cloud result,
double  leaf_size = 0.01 
) [inline]

Definition at line 340 of file openni_tracking.cpp.

template<typename PointType>
void OpenNISegmentTracking< PointType >::normalEstimation ( const CloudConstPtr cloud,
pcl::PointCloud< pcl::Normal > &  result 
) [inline]

Definition at line 395 of file openni_tracking.cpp.

template<typename PointType>
void OpenNISegmentTracking< PointType >::planeProjection ( const CloudConstPtr cloud,
Cloud result,
const pcl::ModelCoefficients::ConstPtr &  coefficients 
) [inline]

Definition at line 371 of file openni_tracking.cpp.

template<typename PointType>
void OpenNISegmentTracking< PointType >::planeSegmentation ( const CloudConstPtr cloud,
pcl::ModelCoefficients &  coefficients,
pcl::PointIndices &  inliers 
) [inline]

Definition at line 355 of file openni_tracking.cpp.

template<typename PointType>
void OpenNISegmentTracking< PointType >::removeZeroPoints ( const CloudConstPtr cloud,
Cloud result 
) [inline]

Definition at line 455 of file openni_tracking.cpp.

template<typename PointType>
void OpenNISegmentTracking< PointType >::run ( ) [inline]

Definition at line 617 of file openni_tracking.cpp.

template<typename PointType>
void OpenNISegmentTracking< PointType >::tracking ( const RefCloudConstPtr cloud) [inline]

Definition at line 404 of file openni_tracking.cpp.

template<typename PointType>
void OpenNISegmentTracking< PointType >::viz_cb ( pcl::visualization::PCLVisualizer viz) [inline]

Definition at line 232 of file openni_tracking.cpp.


Member Data Documentation

template<typename PointType>
CloudPtr OpenNISegmentTracking< PointType >::cloud_hull_

Definition at line 639 of file openni_tracking.cpp.

template<typename PointType>
CloudPtr OpenNISegmentTracking< PointType >::cloud_pass_

Definition at line 635 of file openni_tracking.cpp.

Definition at line 636 of file openni_tracking.cpp.

template<typename PointType>
double OpenNISegmentTracking< PointType >::computation_time_

Definition at line 654 of file openni_tracking.cpp.

template<typename PointType>
int OpenNISegmentTracking< PointType >::counter_

Definition at line 649 of file openni_tracking.cpp.

template<typename PointType>
std::string OpenNISegmentTracking< PointType >::device_id_

Definition at line 644 of file openni_tracking.cpp.

template<typename PointType>
double OpenNISegmentTracking< PointType >::downsampling_grid_size_

Definition at line 656 of file openni_tracking.cpp.

template<typename PointType>
double OpenNISegmentTracking< PointType >::downsampling_time_

Definition at line 655 of file openni_tracking.cpp.

template<typename PointType>
std::vector<pcl::Vertices> OpenNISegmentTracking< PointType >::hull_vertices_

Definition at line 642 of file openni_tracking.cpp.

template<typename PointType>
boost::mutex OpenNISegmentTracking< PointType >::mtx_

Definition at line 645 of file openni_tracking.cpp.

Definition at line 647 of file openni_tracking.cpp.

template<typename PointType>
bool OpenNISegmentTracking< PointType >::new_cloud_

Definition at line 646 of file openni_tracking.cpp.

template<typename PointType>
CloudPtr OpenNISegmentTracking< PointType >::nonplane_cloud_

Definition at line 638 of file openni_tracking.cpp.

template<typename PointType>
pcl::PointCloud<pcl::Normal>::Ptr OpenNISegmentTracking< PointType >::normals_

Definition at line 634 of file openni_tracking.cpp.

template<typename PointType>
CloudPtr OpenNISegmentTracking< PointType >::plane_cloud_

Definition at line 637 of file openni_tracking.cpp.

template<typename PointType>
CloudPtr OpenNISegmentTracking< PointType >::reference_

Definition at line 641 of file openni_tracking.cpp.

template<typename PointType>
CloudPtr OpenNISegmentTracking< PointType >::segmented_cloud_

Definition at line 640 of file openni_tracking.cpp.

template<typename PointType>
boost::shared_ptr<ParticleFilter> OpenNISegmentTracking< PointType >::tracker_

Definition at line 648 of file openni_tracking.cpp.

template<typename PointType>
double OpenNISegmentTracking< PointType >::tracking_time_

Definition at line 653 of file openni_tracking.cpp.

template<typename PointType>
bool OpenNISegmentTracking< PointType >::use_convex_hull_

Definition at line 650 of file openni_tracking.cpp.

Definition at line 633 of file openni_tracking.cpp.

template<typename PointType>
bool OpenNISegmentTracking< PointType >::visualize_non_downsample_

Definition at line 651 of file openni_tracking.cpp.

template<typename PointType>
bool OpenNISegmentTracking< PointType >::visualize_particles_

Definition at line 652 of file openni_tracking.cpp.


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


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