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

#include <ground_based_people_detection_app.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

bool compute (std::vector< pcl::people::PersonCluster< PointT > > &clusters)
 Perform people detection on the input data and return people clusters information.
void extractRGBFromPointCloud (PointCloudPtr input_cloud, pcl::PointCloud< pcl::RGB >::Ptr &output_cloud)
 Extract RGB information from a point cloud and output the corresponding RGB point cloud.
void getDimensionLimits (int &min_points, int &max_points)
 Get minimum and maximum allowed number of points for a person cluster.
Eigen::VectorXf getGround ()
 Get floor coefficients.
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.
PointCloudPtr getNoGroundCloud ()
 Get pointcloud after voxel grid filtering and ground removal.
 GroundBasedPeopleDetectionApp ()
 Constructor.
void setClassifier (pcl::people::PersonClassifier< pcl::RGB > person_classifier)
 Set SVM-based person classifier.
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 setInputCloud (PointCloudPtr &cloud)
 Set the pointer to the input cloud.
void setIntrinsics (Eigen::Matrix3f intrinsics_matrix)
 Set intrinsic parameters of the RGB camera.
void setMinimumDistanceBetweenHeads (float heads_minimum_distance)
 Set minimum distance between persons' heads.
void setSamplingFactor (int sampling_factor)
 Set sampling factor.
void setSensorPortraitOrientation (bool vertical)
 Set sensor orientation (vertical = true means portrait mode, vertical = false means landscape mode).
void setVoxelSize (float voxel_size)
 Set voxel size.
void swapDimensions (pcl::PointCloud< pcl::RGB >::Ptr &cloud)
 Swap rows/cols dimensions of a RGB point cloud (90 degrees counterclockwise rotation).
virtual ~GroundBasedPeopleDetectionApp ()
 Destructor.

Protected Attributes

PointCloudPtr cloud_
 pointer to the input cloud
bool dimension_limits_set_
 true if min_points and max_points have been set by the user, false otherwise
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
Eigen::Matrix3f intrinsics_matrix_
 intrinsic parameters matrix of the RGB camera
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
PointCloudPtr no_ground_cloud_
 pointer to the cloud after voxel grid filtering and ground removal
pcl::people::PersonClassifier
< pcl::RGB
person_classifier_
 SVM-based person classifier.
bool person_classifier_set_flag_
 flag stating if the classifier has been set or not
pcl::PointCloud< pcl::RGB >::Ptr rgb_image_
 pointer to a RGB cloud corresponding to cloud_
int sampling_factor_
 sampling factor used to downsample the point cloud
float sqrt_ground_coeffs_
 ground plane normalization factor
bool vertical_
 if true, the sensor is considered to be vertically placed (portrait mode)
float voxel_size_
 voxel size

Detailed Description

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

Definition at line 71 of file ground_based_people_detection_app.h.


Member Typedef Documentation

Definition at line 75 of file ground_based_people_detection_app.h.

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

Definition at line 77 of file ground_based_people_detection_app.h.

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

Definition at line 76 of file ground_based_people_detection_app.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 47 of file ground_based_people_detection_app.hpp.

Destructor.

Definition at line 333 of file ground_based_people_detection_app.hpp.


Member Function Documentation

template<typename PointT>
bool pcl::people::GroundBasedPeopleDetectionApp< PointT >::compute ( std::vector< pcl::people::PersonCluster< PointT > > &  clusters)

Perform people detection on the input data and return people clusters information.

Parameters:
[out]clustersVector of PersonCluster.
Returns:
true if the compute operation is succesful, false otherwise.

Definition at line 214 of file ground_based_people_detection_app.hpp.

template<typename PointT >
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::extractRGBFromPointCloud ( PointCloudPtr  input_cloud,
pcl::PointCloud< pcl::RGB >::Ptr &  output_cloud 
)

Extract RGB information from a point cloud and output the corresponding RGB point cloud.

Parameters:
[in]input_cloudA pointer to a point cloud containing also RGB information.
[out]output_cloudA pointer to a RGB point cloud.

Definition at line 176 of file ground_based_people_detection_app.hpp.

template<typename PointT >
void pcl::people::GroundBasedPeopleDetectionApp< 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 147 of file ground_based_people_detection_app.hpp.

template<typename PointT >
Eigen::VectorXf pcl::people::GroundBasedPeopleDetectionApp< PointT >::getGround ( )

Get floor coefficients.

Definition at line 160 of file ground_based_people_detection_app.hpp.

template<typename PointT >
void pcl::people::GroundBasedPeopleDetectionApp< 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 140 of file ground_based_people_detection_app.hpp.

Get minimum distance between persons' heads.

Definition at line 154 of file ground_based_people_detection_app.hpp.

Get pointcloud after voxel grid filtering and ground removal.

Definition at line 170 of file ground_based_people_detection_app.hpp.

template<typename PointT >
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::setClassifier ( pcl::people::PersonClassifier< pcl::RGB person_classifier)

Set SVM-based person classifier.

Parameters:
[in]person_classifierNeeded for people detection on RGB data.

Definition at line 100 of file ground_based_people_detection_app.hpp.

template<typename PointT >
void pcl::people::GroundBasedPeopleDetectionApp< 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 120 of file ground_based_people_detection_app.hpp.

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

Set the ground coefficients.

Parameters:
[in]ground_coeffsVector containing the four plane coefficients.

Definition at line 75 of file ground_based_people_detection_app.hpp.

template<typename PointT >
void pcl::people::GroundBasedPeopleDetectionApp< 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 134 of file ground_based_people_detection_app.hpp.

template<typename PointT >
void pcl::people::GroundBasedPeopleDetectionApp< 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 113 of file ground_based_people_detection_app.hpp.

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

Set the pointer to the input cloud.

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

Definition at line 69 of file ground_based_people_detection_app.hpp.

template<typename PointT >
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::setIntrinsics ( Eigen::Matrix3f  intrinsics_matrix)

Set intrinsic parameters of the RGB camera.

Parameters:
[in]intrinsics_matrixRGB camera intrinsic parameters matrix.

Definition at line 94 of file ground_based_people_detection_app.hpp.

template<typename PointT >
void pcl::people::GroundBasedPeopleDetectionApp< 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 128 of file ground_based_people_detection_app.hpp.

template<typename PointT >
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::setSamplingFactor ( int  sampling_factor)

Set sampling factor.

Parameters:
[in]sampling_factorValue of the downsampling factor (in each dimension) which is applied to the raw point cloud (default = 1.).

Definition at line 82 of file ground_based_people_detection_app.hpp.

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

Set sensor orientation (vertical = true means portrait mode, vertical = false means landscape mode).

Parameters:
[in]verticalSet landscape/portait camera orientation (default = false).

Definition at line 107 of file ground_based_people_detection_app.hpp.

template<typename PointT >
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::setVoxelSize ( float  voxel_size)

Set voxel size.

Parameters:
[in]voxel_sizeValue of the voxel dimension (default = 0.06m.).

Definition at line 88 of file ground_based_people_detection_app.hpp.

template<typename PointT >
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::swapDimensions ( pcl::PointCloud< pcl::RGB >::Ptr &  cloud)

Swap rows/cols dimensions of a RGB point cloud (90 degrees counterclockwise rotation).

Parameters:
[in,out]cloudA pointer to a RGB point cloud.

Definition at line 197 of file ground_based_people_detection_app.hpp.


Member Data Documentation

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

pointer to the input cloud

Definition at line 252 of file ground_based_people_detection_app.h.

template<typename PointT>
bool pcl::people::GroundBasedPeopleDetectionApp< PointT >::dimension_limits_set_ [protected]

true if min_points and max_points have been set by the user, false otherwise

Definition at line 280 of file ground_based_people_detection_app.h.

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

ground plane coefficients

Definition at line 246 of file ground_based_people_detection_app.h.

template<typename PointT>
bool pcl::people::GroundBasedPeopleDetectionApp< 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 271 of file ground_based_people_detection_app.h.

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

minimum distance between persons' heads

Definition at line 283 of file ground_based_people_detection_app.h.

template<typename PointT>
Eigen::Matrix3f pcl::people::GroundBasedPeopleDetectionApp< PointT >::intrinsics_matrix_ [protected]

intrinsic parameters matrix of the RGB camera

Definition at line 286 of file ground_based_people_detection_app.h.

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

person clusters maximum height from the ground plane

Definition at line 261 of file ground_based_people_detection_app.h.

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

maximum number of points for a person cluster

Definition at line 274 of file ground_based_people_detection_app.h.

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

person clusters minimum height from the ground plane

Definition at line 264 of file ground_based_people_detection_app.h.

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

minimum number of points for a person cluster

Definition at line 277 of file ground_based_people_detection_app.h.

pointer to the cloud after voxel grid filtering and ground removal

Definition at line 255 of file ground_based_people_detection_app.h.

SVM-based person classifier.

Definition at line 289 of file ground_based_people_detection_app.h.

template<typename PointT>
bool pcl::people::GroundBasedPeopleDetectionApp< PointT >::person_classifier_set_flag_ [protected]

flag stating if the classifier has been set or not

Definition at line 292 of file ground_based_people_detection_app.h.

template<typename PointT>
pcl::PointCloud<pcl::RGB>::Ptr pcl::people::GroundBasedPeopleDetectionApp< PointT >::rgb_image_ [protected]

pointer to a RGB cloud corresponding to cloud_

Definition at line 258 of file ground_based_people_detection_app.h.

template<typename PointT>
int pcl::people::GroundBasedPeopleDetectionApp< PointT >::sampling_factor_ [protected]

sampling factor used to downsample the point cloud

Definition at line 240 of file ground_based_people_detection_app.h.

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

ground plane normalization factor

Definition at line 249 of file ground_based_people_detection_app.h.

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

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

Definition at line 267 of file ground_based_people_detection_app.h.

template<typename PointT>
float pcl::people::GroundBasedPeopleDetectionApp< PointT >::voxel_size_ [protected]

voxel size

Definition at line 243 of file ground_based_people_detection_app.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