Point Cloud Library (PCL)  1.14.1-dev
List of all members | Public Types | Public Member Functions | Protected Attributes
pcl::people::GroundBasedPeopleDetectionApp< PointT > Class Template Reference

GroundBasedPeopleDetectionApp performs people detection on RGB-D data having as input the ground plane coefficients. More...

#include <pcl/people/ground_based_people_detection_app.h>

+ Collaboration diagram for pcl::people::GroundBasedPeopleDetectionApp< PointT >:

Public Types

using PointCloud = pcl::PointCloud< PointT >
 
using PointCloudPtr = typename PointCloud::Ptr
 
using PointCloudConstPtr = typename PointCloud::ConstPtr
 

Public Member Functions

 GroundBasedPeopleDetectionApp ()
 Constructor. More...
 
virtual ~GroundBasedPeopleDetectionApp ()
 Destructor. More...
 
void setInputCloud (PointCloudPtr &cloud)
 Set the pointer to the input cloud. More...
 
void setGround (Eigen::VectorXf &ground_coeffs)
 Set the ground coefficients. More...
 
void setTransformation (const Eigen::Matrix3f &transformation)
 Set the transformation matrix, which is used in order to transform the given point cloud, the ground plane and the intrinsics matrix to the internal coordinate frame. More...
 
void setSamplingFactor (int sampling_factor)
 Set sampling factor. More...
 
void setVoxelSize (float voxel_size)
 Set voxel size. More...
 
void setIntrinsics (Eigen::Matrix3f intrinsics_matrix)
 Set intrinsic parameters of the RGB camera. More...
 
void setClassifier (pcl::people::PersonClassifier< pcl::RGB > person_classifier)
 Set SVM-based person classifier. More...
 
void setFOV (float min, float max)
 Set the field of view of the point cloud in z direction. More...
 
void setSensorPortraitOrientation (bool vertical)
 Set sensor orientation (vertical = true means portrait mode, vertical = false means landscape mode). More...
 
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). More...
 
void setPersonClusterLimits (float min_height, float max_height, float min_width, float max_width)
 Set minimum and maximum allowed height and width for a person cluster. More...
 
void setMinimumDistanceBetweenHeads (float heads_minimum_distance)
 Set minimum distance between persons' heads. More...
 
void getPersonClusterLimits (float &min_height, float &max_height, float &min_width, float &max_width)
 Get the minimum and maximum allowed height and width for a person cluster. More...
 
void getDimensionLimits (int &min_points, int &max_points)
 Get minimum and maximum allowed number of points for a person cluster. More...
 
float getMinimumDistanceBetweenHeads ()
 Get minimum distance between persons' heads. More...
 
Eigen::VectorXf getGround ()
 Get floor coefficients. More...
 
PointCloudPtr getFilteredCloud ()
 Get the filtered point cloud. More...
 
PointCloudPtr getNoGroundCloud ()
 Get pointcloud after voxel grid filtering and ground removal. More...
 
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. More...
 
void swapDimensions (pcl::PointCloud< pcl::RGB >::Ptr &cloud)
 Swap rows/cols dimensions of a RGB point cloud (90 degrees counterclockwise rotation). More...
 
void updateMinMaxPoints ()
 Estimates min_points_ and max_points_ based on the minimal and maximal cluster size and the voxel size. More...
 
void applyTransformationPointCloud ()
 Applies the transformation to the input point cloud. More...
 
void applyTransformationGround ()
 Applies the transformation to the ground plane. More...
 
void applyTransformationIntrinsics ()
 Applies the transformation to the intrinsics matrix. More...
 
void filter ()
 Reduces the input cloud to one point per voxel and limits the field of view. More...
 
bool compute (std::vector< pcl::people::PersonCluster< PointT > > &clusters)
 Perform people detection on the input data and return people clusters information. More...
 

Protected Attributes

int sampling_factor_
 sampling factor used to downsample the point cloud More...
 
float voxel_size_
 voxel size More...
 
Eigen::VectorXf ground_coeffs_
 ground plane coefficients More...
 
bool ground_coeffs_set_
 flag stating whether the ground coefficients have been set or not More...
 
Eigen::VectorXf ground_coeffs_transformed_
 the transformed ground coefficients More...
 
float sqrt_ground_coeffs_
 ground plane normalization factor More...
 
Eigen::Matrix3f transformation_
 rotation matrix which transforms input point cloud to internal people tracker coordinate frame More...
 
bool transformation_set_
 flag stating whether the transformation matrix has been set or not More...
 
PointCloudPtr cloud_
 pointer to the input cloud More...
 
PointCloudPtr cloud_filtered_
 pointer to the filtered cloud More...
 
PointCloudPtr no_ground_cloud_
 pointer to the cloud after voxel grid filtering and ground removal More...
 
pcl::PointCloud< pcl::RGB >::Ptr rgb_image_
 pointer to a RGB cloud corresponding to cloud_ More...
 
float max_height_
 person clusters maximum height from the ground plane More...
 
float min_height_
 person clusters minimum height from the ground plane More...
 
float max_width_
 person clusters maximum width, used to estimate how many points maximally represent a person cluster More...
 
float min_width_
 person clusters minimum width, used to estimate how many points minimally represent a person cluster More...
 
float min_fov_
 the beginning of the field of view in z-direction, should be usually set to zero More...
 
float max_fov_
 the end of the field of view in z-direction More...
 
bool vertical_
 if true, the sensor is considered to be vertically placed (portrait mode) More...
 
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) More...
 
int max_points_
 maximum number of points for a person cluster More...
 
int min_points_
 minimum number of points for a person cluster More...
 
float heads_minimum_distance_
 minimum distance between persons' heads More...
 
Eigen::Matrix3f intrinsics_matrix_
 intrinsic parameters matrix of the RGB camera More...
 
bool intrinsics_matrix_set_
 flag stating whether the intrinsics matrix has been set or not More...
 
Eigen::Matrix3f intrinsics_matrix_transformed_
 the transformed intrinsics matrix More...
 
pcl::people::PersonClassifier< pcl::RGBperson_classifier_
 SVM-based person classifier. More...
 
bool person_classifier_set_flag_
 flag stating if the classifier has been set or not More...
 

Detailed Description

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

GroundBasedPeopleDetectionApp performs people detection on RGB-D data having as input the ground plane coefficients.

It implements the people detection algorithm described here: M. Munaro, F. Basso and E. Menegatti, Tracking people within groups with RGB-D data, In Proceedings of the International Conference on Intelligent Robots and Systems (IROS) 2012, Vilamoura (Portugal), 2012.

Author
Matteo Munaro

Definition at line 68 of file ground_based_people_detection_app.h.

Member Typedef Documentation

◆ PointCloud

Definition at line 72 of file ground_based_people_detection_app.h.

◆ PointCloudConstPtr

Definition at line 74 of file ground_based_people_detection_app.h.

◆ PointCloudPtr

template<typename PointT >
using pcl::people::GroundBasedPeopleDetectionApp< PointT >::PointCloudPtr = typename PointCloud::Ptr

Definition at line 73 of file ground_based_people_detection_app.h.

Constructor & Destructor Documentation

◆ GroundBasedPeopleDetectionApp()

Constructor.

Definition at line 50 of file ground_based_people_detection_app.hpp.

◆ ~GroundBasedPeopleDetectionApp()

template<typename PointT >
pcl::people::GroundBasedPeopleDetectionApp< PointT >::~GroundBasedPeopleDetectionApp ( )
virtualdefault

Destructor.

Member Function Documentation

◆ applyTransformationGround()

template<typename PointT >
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::applyTransformationGround

Applies the transformation to the ground plane.

Definition at line 271 of file ground_based_people_detection_app.hpp.

◆ applyTransformationIntrinsics()

template<typename PointT >
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::applyTransformationIntrinsics

Applies the transformation to the intrinsics matrix.

Definition at line 286 of file ground_based_people_detection_app.hpp.

◆ applyTransformationPointCloud()

template<typename PointT >
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::applyTransformationPointCloud

Applies the transformation to the input point cloud.

Definition at line 260 of file ground_based_people_detection_app.hpp.

References pcl::transformPointCloud().

◆ compute()

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

◆ extractRGBFromPointCloud()

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 222 of file ground_based_people_detection_app.hpp.

References pcl::PointCloud< PointT >::height, pcl::PointCloud< PointT >::points, and pcl::PointCloud< PointT >::width.

◆ filter()

template<typename PointT >
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::filter

◆ getDimensionLimits()

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 187 of file ground_based_people_detection_app.hpp.

◆ getFilteredCloud()

Get the filtered point cloud.

Definition at line 210 of file ground_based_people_detection_app.hpp.

◆ getGround()

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

Get floor coefficients.

Definition at line 200 of file ground_based_people_detection_app.hpp.

◆ getMinimumDistanceBetweenHeads()

template<typename PointT >
float pcl::people::GroundBasedPeopleDetectionApp< PointT >::getMinimumDistanceBetweenHeads

Get minimum distance between persons' heads.

Definition at line 194 of file ground_based_people_detection_app.hpp.

◆ getNoGroundCloud()

Get pointcloud after voxel grid filtering and ground removal.

Definition at line 216 of file ground_based_people_detection_app.hpp.

◆ getPersonClusterLimits()

template<typename PointT >
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::getPersonClusterLimits ( float &  min_height,
float &  max_height,
float &  min_width,
float &  max_width 
)

Get the minimum and maximum allowed height and width for a person cluster.

Parameters
[out]min_heightMinimum allowed height for a person cluster.
[out]max_heightMaximum allowed height for a person cluster.
[out]min_widthMinimum width for a person cluster.
[out]max_widthMaximum width for a person cluster.

Definition at line 178 of file ground_based_people_detection_app.hpp.

◆ setClassifier()

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 129 of file ground_based_people_detection_app.hpp.

◆ setFOV()

template<typename PointT >
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::setFOV ( float  min,
float  max 
)

Set the field of view of the point cloud in z direction.

Parameters
[in]minThe beginning of the field of view in z-direction, should be usually set to zero.
[in]maxThe end of the field of view in z-direction.

Definition at line 136 of file ground_based_people_detection_app.hpp.

◆ setGround()

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 99 of file ground_based_people_detection_app.hpp.

◆ setHeadCentroid()

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 172 of file ground_based_people_detection_app.hpp.

◆ setInputCloud()

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 79 of file ground_based_people_detection_app.hpp.

◆ setIntrinsics()

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 121 of file ground_based_people_detection_app.hpp.

◆ setMinimumDistanceBetweenHeads()

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 166 of file ground_based_people_detection_app.hpp.

◆ setPersonClusterLimits()

template<typename PointT >
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::setPersonClusterLimits ( float  min_height,
float  max_height,
float  min_width,
float  max_width 
)

Set minimum and maximum allowed height and width 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).
[in]min_widthMinimum width for a person cluster (default = 0.1).
[in]max_widthMaximum width for a person cluster (default = 8.0).

Definition at line 156 of file ground_based_people_detection_app.hpp.

◆ setSamplingFactor()

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 108 of file ground_based_people_detection_app.hpp.

◆ setSensorPortraitOrientation()

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/portrait camera orientation (default = false).

Definition at line 143 of file ground_based_people_detection_app.hpp.

◆ setTransformation()

template<typename PointT >
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::setTransformation ( const Eigen::Matrix3f &  transformation)

Set the transformation matrix, which is used in order to transform the given point cloud, the ground plane and the intrinsics matrix to the internal coordinate frame.

Parameters
[in]transformation

Definition at line 85 of file ground_based_people_detection_app.hpp.

◆ setVoxelSize()

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 114 of file ground_based_people_detection_app.hpp.

◆ swapDimensions()

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 243 of file ground_based_people_detection_app.hpp.

References pcl::PointCloud< PointT >::height, pcl::PointCloud< PointT >::points, and pcl::PointCloud< PointT >::width.

◆ updateMinMaxPoints()

template<typename PointT >
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::updateMinMaxPoints

Estimates min_points_ and max_points_ based on the minimal and maximal cluster size and the voxel size.

Definition at line 149 of file ground_based_people_detection_app.hpp.

Member Data Documentation

◆ cloud_

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

pointer to the input cloud

Definition at line 308 of file ground_based_people_detection_app.h.

◆ cloud_filtered_

template<typename PointT >
PointCloudPtr pcl::people::GroundBasedPeopleDetectionApp< PointT >::cloud_filtered_
protected

pointer to the filtered cloud

Definition at line 311 of file ground_based_people_detection_app.h.

◆ ground_coeffs_

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

ground plane coefficients

Definition at line 290 of file ground_based_people_detection_app.h.

◆ ground_coeffs_set_

template<typename PointT >
bool pcl::people::GroundBasedPeopleDetectionApp< PointT >::ground_coeffs_set_
protected

flag stating whether the ground coefficients have been set or not

Definition at line 293 of file ground_based_people_detection_app.h.

◆ ground_coeffs_transformed_

template<typename PointT >
Eigen::VectorXf pcl::people::GroundBasedPeopleDetectionApp< PointT >::ground_coeffs_transformed_
protected

the transformed ground coefficients

Definition at line 296 of file ground_based_people_detection_app.h.

◆ head_centroid_

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 342 of file ground_based_people_detection_app.h.

◆ heads_minimum_distance_

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

minimum distance between persons' heads

Definition at line 351 of file ground_based_people_detection_app.h.

◆ intrinsics_matrix_

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

intrinsic parameters matrix of the RGB camera

Definition at line 354 of file ground_based_people_detection_app.h.

◆ intrinsics_matrix_set_

template<typename PointT >
bool pcl::people::GroundBasedPeopleDetectionApp< PointT >::intrinsics_matrix_set_
protected

flag stating whether the intrinsics matrix has been set or not

Definition at line 357 of file ground_based_people_detection_app.h.

◆ intrinsics_matrix_transformed_

template<typename PointT >
Eigen::Matrix3f pcl::people::GroundBasedPeopleDetectionApp< PointT >::intrinsics_matrix_transformed_
protected

the transformed intrinsics matrix

Definition at line 360 of file ground_based_people_detection_app.h.

◆ max_fov_

template<typename PointT >
float pcl::people::GroundBasedPeopleDetectionApp< PointT >::max_fov_
protected

the end of the field of view in z-direction

Definition at line 335 of file ground_based_people_detection_app.h.

◆ max_height_

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

person clusters maximum height from the ground plane

Definition at line 320 of file ground_based_people_detection_app.h.

◆ max_points_

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

maximum number of points for a person cluster

Definition at line 345 of file ground_based_people_detection_app.h.

◆ max_width_

template<typename PointT >
float pcl::people::GroundBasedPeopleDetectionApp< PointT >::max_width_
protected

person clusters maximum width, used to estimate how many points maximally represent a person cluster

Definition at line 326 of file ground_based_people_detection_app.h.

◆ min_fov_

template<typename PointT >
float pcl::people::GroundBasedPeopleDetectionApp< PointT >::min_fov_
protected

the beginning of the field of view in z-direction, should be usually set to zero

Definition at line 332 of file ground_based_people_detection_app.h.

◆ min_height_

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

person clusters minimum height from the ground plane

Definition at line 323 of file ground_based_people_detection_app.h.

◆ min_points_

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

minimum number of points for a person cluster

Definition at line 348 of file ground_based_people_detection_app.h.

◆ min_width_

template<typename PointT >
float pcl::people::GroundBasedPeopleDetectionApp< PointT >::min_width_
protected

person clusters minimum width, used to estimate how many points minimally represent a person cluster

Definition at line 329 of file ground_based_people_detection_app.h.

◆ no_ground_cloud_

template<typename PointT >
PointCloudPtr pcl::people::GroundBasedPeopleDetectionApp< PointT >::no_ground_cloud_
protected

pointer to the cloud after voxel grid filtering and ground removal

Definition at line 314 of file ground_based_people_detection_app.h.

◆ person_classifier_

template<typename PointT >
pcl::people::PersonClassifier<pcl::RGB> pcl::people::GroundBasedPeopleDetectionApp< PointT >::person_classifier_
protected

SVM-based person classifier.

Definition at line 363 of file ground_based_people_detection_app.h.

◆ person_classifier_set_flag_

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 366 of file ground_based_people_detection_app.h.

◆ rgb_image_

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 317 of file ground_based_people_detection_app.h.

◆ sampling_factor_

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

sampling factor used to downsample the point cloud

Definition at line 284 of file ground_based_people_detection_app.h.

◆ sqrt_ground_coeffs_

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

ground plane normalization factor

Definition at line 299 of file ground_based_people_detection_app.h.

◆ transformation_

template<typename PointT >
Eigen::Matrix3f pcl::people::GroundBasedPeopleDetectionApp< PointT >::transformation_
protected

rotation matrix which transforms input point cloud to internal people tracker coordinate frame

Definition at line 302 of file ground_based_people_detection_app.h.

◆ transformation_set_

template<typename PointT >
bool pcl::people::GroundBasedPeopleDetectionApp< PointT >::transformation_set_
protected

flag stating whether the transformation matrix has been set or not

Definition at line 305 of file ground_based_people_detection_app.h.

◆ vertical_

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 338 of file ground_based_people_detection_app.h.

◆ voxel_size_

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

voxel size

Definition at line 287 of file ground_based_people_detection_app.h.


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