Public Types | Public Member Functions | Protected Attributes
pcl::people::HeadBasedSubclustering< PointT > Class Template Reference

#include <head_based_subcluster.h>

List of all members.

Public Types

typedef pcl::PointCloud< PointTPointCloud
typedef boost::shared_ptr
< const PointCloud
PointCloudConstPtr
typedef boost::shared_ptr
< PointCloud
PointCloudPtr

Public Member Functions

void createSubClusters (pcl::people::PersonCluster< PointT > &cluster, int maxima_number_after_filtering, std::vector< int > &maxima_cloud_indices_filtered, std::vector< pcl::people::PersonCluster< PointT > > &subclusters)
 Create subclusters centered on the heads position from the current cluster.
void getDimensionLimits (int &min_points, int &max_points)
 Get minimum and maximum allowed number of points for a person cluster.
void getHeightLimits (float &min_height, float &max_height)
 Get minimum and maximum allowed height for a person cluster.
float getMinimumDistanceBetweenHeads ()
 Get minimum distance between persons' heads.
 HeadBasedSubclustering ()
 Constructor.
void mergeClustersCloseInFloorCoordinates (std::vector< pcl::people::PersonCluster< PointT > > &input_clusters, std::vector< pcl::people::PersonCluster< PointT > > &output_clusters)
 Merge clusters close in floor coordinates.
void setDimensionLimits (int min_points, int max_points)
 Set minimum and maximum allowed number of points for a person cluster.
void setGround (Eigen::VectorXf &ground_coeffs)
 Set the ground coefficients.
void setHeadCentroid (bool head_centroid)
 Set head_centroid_ to true (person centroid is in the head) or false (person centroid is the whole body centroid).
void setHeightLimits (float min_height, float max_height)
 Set minimum and maximum allowed height for a person cluster.
void setInitialClusters (std::vector< pcl::PointIndices > &cluster_indices)
 Set initial cluster indices.
void setInputCloud (PointCloudPtr &cloud)
 Set input cloud.
void setMinimumDistanceBetweenHeads (float heads_minimum_distance)
 Set minimum distance between persons' heads.
void setSensorPortraitOrientation (bool vertical)
 Set sensor orientation to landscape mode (false) or portrait mode (true).
void subcluster (std::vector< pcl::people::PersonCluster< PointT > > &clusters)
 Compute subclusters and return them into a vector of PersonCluster.
virtual ~HeadBasedSubclustering ()
 Destructor.

Protected Attributes

PointCloudPtr cloud_
 pointer to the input cloud
std::vector< pcl::PointIndicescluster_indices_
 initial clusters indices
Eigen::VectorXf ground_coeffs_
 ground plane coefficients
bool head_centroid_
 if true, the person centroid is computed as the centroid of the cluster points belonging to the head if false, the person centroid is computed as the centroid of the whole cluster points (default = true)
float heads_minimum_distance_
 minimum distance between persons' heads
float max_height_
 person clusters maximum height from the ground plane
int max_points_
 maximum number of points for a person cluster
float min_height_
 person clusters minimum height from the ground plane
int min_points_
 minimum number of points for a person cluster
float sqrt_ground_coeffs_
 ground plane normalization factor
bool vertical_
 if true, the sensor is considered to be vertically placed (portrait mode)

Detailed Description

template<typename PointT>
class pcl::people::HeadBasedSubclustering< PointT >

Definition at line 59 of file head_based_subcluster.h.


Member Typedef Documentation

Definition at line 63 of file head_based_subcluster.h.

template<typename PointT>
typedef boost::shared_ptr<const PointCloud> pcl::people::HeadBasedSubclustering< PointT >::PointCloudConstPtr

Definition at line 65 of file head_based_subcluster.h.

template<typename PointT>
typedef boost::shared_ptr<PointCloud> pcl::people::HeadBasedSubclustering< PointT >::PointCloudPtr

Definition at line 64 of file head_based_subcluster.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 47 of file head_based_subcluster.hpp.

template<typename PointT >
pcl::people::HeadBasedSubclustering< PointT >::~HeadBasedSubclustering ( ) [virtual]

Destructor.

Definition at line 336 of file head_based_subcluster.hpp.


Member Function Documentation

template<typename PointT >
void pcl::people::HeadBasedSubclustering< PointT >::createSubClusters ( pcl::people::PersonCluster< PointT > &  cluster,
int  maxima_number_after_filtering,
std::vector< int > &  maxima_cloud_indices_filtered,
std::vector< pcl::people::PersonCluster< PointT > > &  subclusters 
)

Create subclusters centered on the heads position from the current cluster.

Parameters:
[in]clusterA PersonCluster.
[in]maxima_numberNumber of local maxima to use as centers of the new cluster.
[in]maxima_cloud_indicesCloud indices of local maxima to use as centers of the new cluster.
[out]subclustersOutput vector of PersonCluster objects derived from the input cluster.

Definition at line 195 of file head_based_subcluster.hpp.

template<typename PointT >
void pcl::people::HeadBasedSubclustering< PointT >::getDimensionLimits ( int &  min_points,
int &  max_points 
)

Get minimum and maximum allowed number of points for a person cluster.

Parameters:
[out]min_pointsMinimum allowed number of points for a person cluster.
[out]max_pointsMaximum allowed number of points for a person cluster.

Definition at line 121 of file head_based_subcluster.hpp.

template<typename PointT >
void pcl::people::HeadBasedSubclustering< PointT >::getHeightLimits ( float &  min_height,
float &  max_height 
)

Get minimum and maximum allowed height for a person cluster.

Parameters:
[out]min_heightMinimum allowed height for a person cluster.
[out]max_heightMaximum allowed height for a person cluster.

Definition at line 114 of file head_based_subcluster.hpp.

Get minimum distance between persons' heads.

Definition at line 128 of file head_based_subcluster.hpp.

template<typename PointT >
void pcl::people::HeadBasedSubclustering< PointT >::mergeClustersCloseInFloorCoordinates ( std::vector< pcl::people::PersonCluster< PointT > > &  input_clusters,
std::vector< pcl::people::PersonCluster< PointT > > &  output_clusters 
)

Merge clusters close in floor coordinates.

Parameters:
[in]input_clustersInput vector of PersonCluster.
[in]output_clustersOutput vector of PersonCluster (after merging).

Definition at line 134 of file head_based_subcluster.hpp.

template<typename PointT >
void pcl::people::HeadBasedSubclustering< PointT >::setDimensionLimits ( int  min_points,
int  max_points 
)

Set minimum and maximum allowed number of points for a person cluster.

Parameters:
[in]min_pointsMinimum allowed number of points for a person cluster.
[in]max_pointsMaximum allowed number of points for a person cluster.

Definition at line 95 of file head_based_subcluster.hpp.

template<typename PointT >
void pcl::people::HeadBasedSubclustering< PointT >::setGround ( Eigen::VectorXf &  ground_coeffs)

Set the ground coefficients.

Parameters:
[in]ground_coeffsThe ground plane coefficients.

Definition at line 69 of file head_based_subcluster.hpp.

template<typename PointT >
void pcl::people::HeadBasedSubclustering< PointT >::setHeadCentroid ( bool  head_centroid)

Set head_centroid_ to true (person centroid is in the head) or false (person centroid is the whole body centroid).

Parameters:
[in]head_centroidSet the location of the person centroid (head or body center) (default = true).

Definition at line 108 of file head_based_subcluster.hpp.

template<typename PointT >
void pcl::people::HeadBasedSubclustering< PointT >::setHeightLimits ( float  min_height,
float  max_height 
)

Set minimum and maximum allowed height for a person cluster.

Parameters:
[in]min_heightMinimum allowed height for a person cluster (default = 1.3).
[in]max_heightMaximum allowed height for a person cluster (default = 2.3).

Definition at line 88 of file head_based_subcluster.hpp.

template<typename PointT >
void pcl::people::HeadBasedSubclustering< PointT >::setInitialClusters ( std::vector< pcl::PointIndices > &  cluster_indices)

Set initial cluster indices.

Parameters:
[in]cluster_indicesPoint cloud indices corresponding to the initial clusters (before subclustering).

Definition at line 76 of file head_based_subcluster.hpp.

template<typename PointT >
void pcl::people::HeadBasedSubclustering< PointT >::setInputCloud ( PointCloudPtr cloud)

Set input cloud.

Parameters:
[in]cloudA pointer to the input point cloud.

Definition at line 63 of file head_based_subcluster.hpp.

template<typename PointT >
void pcl::people::HeadBasedSubclustering< PointT >::setMinimumDistanceBetweenHeads ( float  heads_minimum_distance)

Set minimum distance between persons' heads.

Parameters:
[in]heads_minimum_distanceMinimum allowed distance between persons' heads (default = 0.3).

Definition at line 102 of file head_based_subcluster.hpp.

template<typename PointT >
void pcl::people::HeadBasedSubclustering< PointT >::setSensorPortraitOrientation ( bool  vertical)

Set sensor orientation to landscape mode (false) or portrait mode (true).

Parameters:
[in]verticalLandscape (false) or portrait (true) mode (default = false).

Definition at line 82 of file head_based_subcluster.hpp.

template<typename PointT >
void pcl::people::HeadBasedSubclustering< PointT >::subcluster ( std::vector< pcl::people::PersonCluster< PointT > > &  clusters)

Compute subclusters and return them into a vector of PersonCluster.

Parameters:
[in]clustersVector of PersonCluster.

Definition at line 255 of file head_based_subcluster.hpp.


Member Data Documentation

template<typename PointT>
PointCloudPtr pcl::people::HeadBasedSubclustering< PointT >::cloud_ [protected]

pointer to the input cloud

Definition at line 204 of file head_based_subcluster.h.

template<typename PointT>
std::vector<pcl::PointIndices> pcl::people::HeadBasedSubclustering< PointT >::cluster_indices_ [protected]

initial clusters indices

Definition at line 201 of file head_based_subcluster.h.

template<typename PointT>
Eigen::VectorXf pcl::people::HeadBasedSubclustering< PointT >::ground_coeffs_ [protected]

ground plane coefficients

Definition at line 195 of file head_based_subcluster.h.

template<typename PointT>
bool pcl::people::HeadBasedSubclustering< PointT >::head_centroid_ [protected]

if true, the person centroid is computed as the centroid of the cluster points belonging to the head if false, the person centroid is computed as the centroid of the whole cluster points (default = true)

Definition at line 217 of file head_based_subcluster.h.

template<typename PointT>
float pcl::people::HeadBasedSubclustering< PointT >::heads_minimum_distance_ [protected]

minimum distance between persons' heads

Definition at line 226 of file head_based_subcluster.h.

template<typename PointT>
float pcl::people::HeadBasedSubclustering< PointT >::max_height_ [protected]

person clusters maximum height from the ground plane

Definition at line 207 of file head_based_subcluster.h.

template<typename PointT>
int pcl::people::HeadBasedSubclustering< PointT >::max_points_ [protected]

maximum number of points for a person cluster

Definition at line 220 of file head_based_subcluster.h.

template<typename PointT>
float pcl::people::HeadBasedSubclustering< PointT >::min_height_ [protected]

person clusters minimum height from the ground plane

Definition at line 210 of file head_based_subcluster.h.

template<typename PointT>
int pcl::people::HeadBasedSubclustering< PointT >::min_points_ [protected]

minimum number of points for a person cluster

Definition at line 223 of file head_based_subcluster.h.

template<typename PointT>
float pcl::people::HeadBasedSubclustering< PointT >::sqrt_ground_coeffs_ [protected]

ground plane normalization factor

Definition at line 198 of file head_based_subcluster.h.

template<typename PointT>
bool pcl::people::HeadBasedSubclustering< PointT >::vertical_ [protected]

if true, the sensor is considered to be vertically placed (portrait mode)

Definition at line 213 of file head_based_subcluster.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:44:32