Point Cloud Library (PCL)
1.14.1-dev
|
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>
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::RGB > | person_classifier_ |
SVM-based person classifier. More... | |
bool | person_classifier_set_flag_ |
flag stating if the classifier has been set or not More... | |
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.
Definition at line 68 of file ground_based_people_detection_app.h.
using pcl::people::GroundBasedPeopleDetectionApp< PointT >::PointCloud = pcl::PointCloud<PointT> |
Definition at line 72 of file ground_based_people_detection_app.h.
using pcl::people::GroundBasedPeopleDetectionApp< PointT >::PointCloudConstPtr = typename PointCloud::ConstPtr |
Definition at line 74 of file ground_based_people_detection_app.h.
using pcl::people::GroundBasedPeopleDetectionApp< PointT >::PointCloudPtr = typename PointCloud::Ptr |
Definition at line 73 of file ground_based_people_detection_app.h.
pcl::people::GroundBasedPeopleDetectionApp< PointT >::GroundBasedPeopleDetectionApp |
Constructor.
Definition at line 50 of file ground_based_people_detection_app.hpp.
|
virtualdefault |
Destructor.
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.
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.
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().
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.
[out] | clusters | Vector of PersonCluster. |
Definition at line 311 of file ground_based_people_detection_app.hpp.
References pcl::EuclideanClusterExtraction< PointT >::extract(), pcl::FilterIndices< PointT >::filter(), pcl::SampleConsensusModelPlane< PointT >::optimizeModelCoefficients(), pcl::SampleConsensusModelPlane< PointT >::selectWithinDistance(), pcl::EuclideanClusterExtraction< PointT >::setClusterTolerance(), pcl::people::HeadBasedSubclustering< PointT >::setGround(), pcl::people::HeadBasedSubclustering< PointT >::setHeightLimits(), pcl::PCLBase< PointT >::setIndices(), pcl::people::HeadBasedSubclustering< PointT >::setInitialClusters(), pcl::PCLBase< PointT >::setInputCloud(), pcl::search::KdTree< PointT, Tree >::setInputCloud(), pcl::people::HeadBasedSubclustering< PointT >::setInputCloud(), pcl::EuclideanClusterExtraction< PointT >::setMaxClusterSize(), pcl::EuclideanClusterExtraction< PointT >::setMinClusterSize(), pcl::people::HeadBasedSubclustering< PointT >::setMinimumDistanceBetweenHeads(), pcl::FilterIndices< PointT >::setNegative(), pcl::EuclideanClusterExtraction< PointT >::setSearchMethod(), pcl::people::HeadBasedSubclustering< PointT >::setSensorPortraitOrientation(), and pcl::people::HeadBasedSubclustering< PointT >::subcluster().
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.
[in] | input_cloud | A pointer to a point cloud containing also RGB information. |
[out] | output_cloud | A 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.
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::filter |
Reduces the input cloud to one point per voxel and limits the field of view.
Definition at line 299 of file ground_based_people_detection_app.hpp.
References pcl::Filter< PointT >::filter(), pcl::VoxelGrid< PointT >::setFilterFieldName(), pcl::VoxelGrid< PointT >::setFilterLimits(), pcl::PCLBase< PointT >::setInputCloud(), and pcl::VoxelGrid< PointT >::setLeafSize().
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::getDimensionLimits | ( | int & | min_points, |
int & | max_points | ||
) |
Get minimum and maximum allowed number of points for a person cluster.
[out] | min_points | Minimum allowed number of points for a person cluster. |
[out] | max_points | Maximum allowed number of points for a person cluster. |
Definition at line 187 of file ground_based_people_detection_app.hpp.
pcl::people::GroundBasedPeopleDetectionApp< PointT >::PointCloudPtr pcl::people::GroundBasedPeopleDetectionApp< PointT >::getFilteredCloud |
Get the filtered point cloud.
Definition at line 210 of file ground_based_people_detection_app.hpp.
Eigen::VectorXf pcl::people::GroundBasedPeopleDetectionApp< PointT >::getGround |
Get floor coefficients.
Definition at line 200 of file ground_based_people_detection_app.hpp.
float pcl::people::GroundBasedPeopleDetectionApp< PointT >::getMinimumDistanceBetweenHeads |
Get minimum distance between persons' heads.
Definition at line 194 of file ground_based_people_detection_app.hpp.
pcl::people::GroundBasedPeopleDetectionApp< PointT >::PointCloudPtr pcl::people::GroundBasedPeopleDetectionApp< PointT >::getNoGroundCloud |
Get pointcloud after voxel grid filtering and ground removal.
Definition at line 216 of file ground_based_people_detection_app.hpp.
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.
[out] | min_height | Minimum allowed height for a person cluster. |
[out] | max_height | Maximum allowed height for a person cluster. |
[out] | min_width | Minimum width for a person cluster. |
[out] | max_width | Maximum width for a person cluster. |
Definition at line 178 of file ground_based_people_detection_app.hpp.
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::setClassifier | ( | pcl::people::PersonClassifier< pcl::RGB > | person_classifier | ) |
Set SVM-based person classifier.
[in] | person_classifier | Needed for people detection on RGB data. |
Definition at line 129 of file ground_based_people_detection_app.hpp.
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::setFOV | ( | float | min, |
float | max | ||
) |
Set the field of view of the point cloud in z direction.
[in] | min | The beginning of the field of view in z-direction, should be usually set to zero. |
[in] | max | The end of the field of view in z-direction. |
Definition at line 136 of file ground_based_people_detection_app.hpp.
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::setGround | ( | Eigen::VectorXf & | ground_coeffs | ) |
Set the ground coefficients.
[in] | ground_coeffs | Vector containing the four plane coefficients. |
Definition at line 99 of file ground_based_people_detection_app.hpp.
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).
[in] | head_centroid | Set the location of the person centroid (head or body center) (default = true). |
Definition at line 172 of file ground_based_people_detection_app.hpp.
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::setInputCloud | ( | PointCloudPtr & | cloud | ) |
Set the pointer to the input cloud.
[in] | cloud | A pointer to the input cloud. |
Definition at line 79 of file ground_based_people_detection_app.hpp.
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::setIntrinsics | ( | Eigen::Matrix3f | intrinsics_matrix | ) |
Set intrinsic parameters of the RGB camera.
[in] | intrinsics_matrix | RGB camera intrinsic parameters matrix. |
Definition at line 121 of file ground_based_people_detection_app.hpp.
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::setMinimumDistanceBetweenHeads | ( | float | heads_minimum_distance | ) |
Set minimum distance between persons' heads.
[in] | heads_minimum_distance | Minimum allowed distance between persons' heads (default = 0.3). |
Definition at line 166 of file ground_based_people_detection_app.hpp.
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.
[in] | min_height | Minimum allowed height for a person cluster (default = 1.3). |
[in] | max_height | Maximum allowed height for a person cluster (default = 2.3). |
[in] | min_width | Minimum width for a person cluster (default = 0.1). |
[in] | max_width | Maximum width for a person cluster (default = 8.0). |
Definition at line 156 of file ground_based_people_detection_app.hpp.
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::setSamplingFactor | ( | int | sampling_factor | ) |
Set sampling factor.
[in] | sampling_factor | Value 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.
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::setSensorPortraitOrientation | ( | bool | vertical | ) |
Set sensor orientation (vertical = true means portrait mode, vertical = false means landscape mode).
[in] | vertical | Set landscape/portrait camera orientation (default = false). |
Definition at line 143 of file ground_based_people_detection_app.hpp.
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.
[in] | transformation |
Definition at line 85 of file ground_based_people_detection_app.hpp.
void pcl::people::GroundBasedPeopleDetectionApp< PointT >::setVoxelSize | ( | float | voxel_size | ) |
Set voxel size.
[in] | voxel_size | Value of the voxel dimension (default = 0.06m.). |
Definition at line 114 of file ground_based_people_detection_app.hpp.
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).
[in,out] | cloud | A 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.
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.
|
protected |
pointer to the input cloud
Definition at line 308 of file ground_based_people_detection_app.h.
|
protected |
pointer to the filtered cloud
Definition at line 311 of file ground_based_people_detection_app.h.
|
protected |
ground plane coefficients
Definition at line 290 of file ground_based_people_detection_app.h.
|
protected |
flag stating whether the ground coefficients have been set or not
Definition at line 293 of file ground_based_people_detection_app.h.
|
protected |
the transformed ground coefficients
Definition at line 296 of file ground_based_people_detection_app.h.
|
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.
|
protected |
minimum distance between persons' heads
Definition at line 351 of file ground_based_people_detection_app.h.
|
protected |
intrinsic parameters matrix of the RGB camera
Definition at line 354 of file ground_based_people_detection_app.h.
|
protected |
flag stating whether the intrinsics matrix has been set or not
Definition at line 357 of file ground_based_people_detection_app.h.
|
protected |
the transformed intrinsics matrix
Definition at line 360 of file ground_based_people_detection_app.h.
|
protected |
the end of the field of view in z-direction
Definition at line 335 of file ground_based_people_detection_app.h.
|
protected |
person clusters maximum height from the ground plane
Definition at line 320 of file ground_based_people_detection_app.h.
|
protected |
maximum number of points for a person cluster
Definition at line 345 of file ground_based_people_detection_app.h.
|
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.
|
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.
|
protected |
person clusters minimum height from the ground plane
Definition at line 323 of file ground_based_people_detection_app.h.
|
protected |
minimum number of points for a person cluster
Definition at line 348 of file ground_based_people_detection_app.h.
|
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.
|
protected |
pointer to the cloud after voxel grid filtering and ground removal
Definition at line 314 of file ground_based_people_detection_app.h.
|
protected |
SVM-based person classifier.
Definition at line 363 of file ground_based_people_detection_app.h.
|
protected |
flag stating if the classifier has been set or not
Definition at line 366 of file ground_based_people_detection_app.h.
|
protected |
pointer to a RGB cloud corresponding to cloud_
Definition at line 317 of file ground_based_people_detection_app.h.
|
protected |
sampling factor used to downsample the point cloud
Definition at line 284 of file ground_based_people_detection_app.h.
|
protected |
ground plane normalization factor
Definition at line 299 of file ground_based_people_detection_app.h.
|
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.
|
protected |
flag stating whether the transformation matrix has been set or not
Definition at line 305 of file ground_based_people_detection_app.h.
|
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.
|
protected |
voxel size
Definition at line 287 of file ground_based_people_detection_app.h.