Point Cloud Library (PCL)  1.8.1-dev
ground_based_people_detection_app.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2013-, Open Perception, Inc.
6  *
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the copyright holder(s) nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * ground_based_people_detection_app.h
37  * Created on: Nov 30, 2012
38  * Author: Matteo Munaro
39  */
40 
41 #ifndef PCL_PEOPLE_GROUND_BASED_PEOPLE_DETECTION_APP_H_
42 #define PCL_PEOPLE_GROUND_BASED_PEOPLE_DETECTION_APP_H_
43 
44 #include <pcl/point_types.h>
45 #include <pcl/sample_consensus/sac_model_plane.h>
46 #include <pcl/sample_consensus/ransac.h>
47 #include <pcl/filters/extract_indices.h>
48 #include <pcl/segmentation/extract_clusters.h>
49 #include <pcl/kdtree/kdtree.h>
50 #include <pcl/filters/voxel_grid.h>
51 #include <pcl/people/person_cluster.h>
52 #include <pcl/people/head_based_subcluster.h>
53 #include <pcl/people/person_classifier.h>
54 #include <pcl/common/transforms.h>
55 
56 namespace pcl
57 {
58  namespace people
59  {
60  /** \brief GroundBasedPeopleDetectionApp performs people detection on RGB-D data having as input the ground plane coefficients.
61  * It implements the people detection algorithm described here:
62  * M. Munaro, F. Basso and E. Menegatti,
63  * Tracking people within groups with RGB-D data,
64  * In Proceedings of the International Conference on Intelligent Robots and Systems (IROS) 2012, Vilamoura (Portugal), 2012.
65  *
66  * \author Matteo Munaro
67  * \ingroup people
68  */
69  template <typename PointT> class GroundBasedPeopleDetectionApp;
70 
71  template <typename PointT>
73  {
74  public:
75 
77  typedef boost::shared_ptr<PointCloud> PointCloudPtr;
78  typedef boost::shared_ptr<const PointCloud> PointCloudConstPtr;
79 
80  /** \brief Constructor. */
82 
83  /** \brief Destructor. */
85 
86  /**
87  * \brief Set the pointer to the input cloud.
88  *
89  * \param[in] cloud A pointer to the input cloud.
90  */
91  void
93 
94  /**
95  * \brief Set the ground coefficients.
96  *
97  * \param[in] ground_coeffs Vector containing the four plane coefficients.
98  */
99  void
100  setGround (Eigen::VectorXf& ground_coeffs);
101 
102  /**
103  * \brief 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.
104  * \param[in] transformation
105  */
106  void
107  setTransformation (const Eigen::Matrix3f& transformation);
108 
109  /**
110  * \brief Set sampling factor.
111  *
112  * \param[in] sampling_factor Value of the downsampling factor (in each dimension) which is applied to the raw point cloud (default = 1.).
113  */
114  void
115  setSamplingFactor (int sampling_factor);
116 
117  /**
118  * \brief Set voxel size.
119  *
120  * \param[in] voxel_size Value of the voxel dimension (default = 0.06m.).
121  */
122  void
123  setVoxelSize (float voxel_size);
124 
125  /**
126  * \brief Set intrinsic parameters of the RGB camera.
127  *
128  * \param[in] intrinsics_matrix RGB camera intrinsic parameters matrix.
129  */
130  void
131  setIntrinsics (Eigen::Matrix3f intrinsics_matrix);
132 
133  /**
134  * \brief Set SVM-based person classifier.
135  *
136  * \param[in] person_classifier Needed for people detection on RGB data.
137  */
138  void
140 
141  /**
142  * \brief Set the field of view of the point cloud in z direction.
143  *
144  * \param[in] min The beginning of the field of view in z-direction, should be usually set to zero.
145  * \param[in] max The end of the field of view in z-direction.
146  */
147  void
148  setFOV (float min, float max);
149 
150  /**
151  * \brief Set sensor orientation (vertical = true means portrait mode, vertical = false means landscape mode).
152  *
153  * \param[in] vertical Set landscape/portait camera orientation (default = false).
154  */
155  void
156  setSensorPortraitOrientation (bool vertical);
157 
158  /**
159  * \brief Set head_centroid_ to true (person centroid is in the head) or false (person centroid is the whole body centroid).
160  *
161  * \param[in] head_centroid Set the location of the person centroid (head or body center) (default = true).
162  */
163  void
164  setHeadCentroid (bool head_centroid);
165 
166  /**
167  * \brief Set minimum and maximum allowed height and width for a person cluster.
168  *
169  * \param[in] min_height Minimum allowed height for a person cluster (default = 1.3).
170  * \param[in] max_height Maximum allowed height for a person cluster (default = 2.3).
171  * \param[in] min_width Minimum width for a person cluster (default = 0.1).
172  * \param[in] max_width Maximum width for a person cluster (default = 8.0).
173  */
174  void
175  setPersonClusterLimits (float min_height, float max_height, float min_width, float max_width);
176 
177  /**
178  * \brief Set minimum distance between persons' heads.
179  *
180  * \param[in] heads_minimum_distance Minimum allowed distance between persons' heads (default = 0.3).
181  */
182  void
183  setMinimumDistanceBetweenHeads (float heads_minimum_distance);
184 
185  /**
186  * \brief Get the minimum and maximum allowed height and width for a person cluster.
187  *
188  * \param[out] min_height Minimum allowed height for a person cluster.
189  * \param[out] max_height Maximum allowed height for a person cluster.
190  * \param[out] min_width Minimum width for a person cluster.
191  * \param[out] max_width Maximum width for a person cluster.
192  */
193  void
194  getPersonClusterLimits (float& min_height, float& max_height, float& min_width, float& max_width);
195 
196  /**
197  * \brief Get minimum and maximum allowed number of points for a person cluster.
198  *
199  * \param[out] min_points Minimum allowed number of points for a person cluster.
200  * \param[out] max_points Maximum allowed number of points for a person cluster.
201  */
202  void
203  getDimensionLimits (int& min_points, int& max_points);
204 
205  /**
206  * \brief Get minimum distance between persons' heads.
207  */
208  float
210 
211  /**
212  * \brief Get floor coefficients.
213  */
214  Eigen::VectorXf
215  getGround ();
216 
217  /**
218  * \brief Get the filtered point cloud.
219  */
221  getFilteredCloud ();
222 
223  /**
224  * \brief Get pointcloud after voxel grid filtering and ground removal.
225  */
227  getNoGroundCloud ();
228 
229  /**
230  * \brief Extract RGB information from a point cloud and output the corresponding RGB point cloud.
231  *
232  * \param[in] input_cloud A pointer to a point cloud containing also RGB information.
233  * \param[out] output_cloud A pointer to a RGB point cloud.
234  */
235  void
237 
238  /**
239  * \brief Swap rows/cols dimensions of a RGB point cloud (90 degrees counterclockwise rotation).
240  *
241  * \param[in,out] cloud A pointer to a RGB point cloud.
242  */
243  void
245 
246  /**
247  * \brief Estimates min_points_ and max_points_ based on the minimal and maximal cluster size and the voxel size.
248  */
249  void
251 
252  /**
253  * \brief Applies the transformation to the input point cloud.
254  */
255  void
257 
258  /**
259  * \brief Applies the transformation to the ground plane.
260  */
261  void
263 
264  /**
265  * \brief Applies the transformation to the intrinsics matrix.
266  */
267  void
269 
270  /**
271  * \brief Reduces the input cloud to one point per voxel and limits the field of view.
272  */
273  void
274  filter ();
275 
276  /**
277  * \brief Perform people detection on the input data and return people clusters information.
278  *
279  * \param[out] clusters Vector of PersonCluster.
280  *
281  * \return true if the compute operation is successful, false otherwise.
282  */
283  bool
284  compute (std::vector<pcl::people::PersonCluster<PointT> >& clusters);
285 
286  protected:
287  /** \brief sampling factor used to downsample the point cloud */
289 
290  /** \brief voxel size */
291  float voxel_size_;
292 
293  /** \brief ground plane coefficients */
294  Eigen::VectorXf ground_coeffs_;
295 
296  /** \brief flag stating whether the ground coefficients have been set or not */
298 
299  /** \brief the transformed ground coefficients */
300  Eigen::VectorXf ground_coeffs_transformed_;
301 
302  /** \brief ground plane normalization factor */
304 
305  /** \brief rotation matrix which transforms input point cloud to internal people tracker coordinate frame */
306  Eigen::Matrix3f transformation_;
307 
308  /** \brief flag stating whether the transformation matrix has been set or not */
310 
311  /** \brief pointer to the input cloud */
313 
314  /** \brief pointer to the filtered cloud */
316 
317  /** \brief pointer to the cloud after voxel grid filtering and ground removal */
319 
320  /** \brief pointer to a RGB cloud corresponding to cloud_ */
322 
323  /** \brief person clusters maximum height from the ground plane */
324  float max_height_;
325 
326  /** \brief person clusters minimum height from the ground plane */
327  float min_height_;
328 
329  /** \brief person clusters maximum width, used to estimate how many points maximally represent a person cluster */
330  float max_width_;
331 
332  /** \brief person clusters minimum width, used to estimate how many points minimally represent a person cluster */
333  float min_width_;
334 
335  /** \brief the beginning of the field of view in z-direction, should be usually set to zero */
336  float min_fov_;
337 
338  /** \brief the end of the field of view in z-direction */
339  float max_fov_;
340 
341  /** \brief if true, the sensor is considered to be vertically placed (portrait mode) */
342  bool vertical_;
343 
344  /** \brief if true, the person centroid is computed as the centroid of the cluster points belonging to the head;
345  * if false, the person centroid is computed as the centroid of the whole cluster points (default = true) */
346  bool head_centroid_; // if true, the person centroid is computed as the centroid of the cluster points belonging to the head (default = true)
347  // if false, the person centroid is computed as the centroid of the whole cluster points
348  /** \brief maximum number of points for a person cluster */
350 
351  /** \brief minimum number of points for a person cluster */
353 
354  /** \brief minimum distance between persons' heads */
356 
357  /** \brief intrinsic parameters matrix of the RGB camera */
358  Eigen::Matrix3f intrinsics_matrix_;
359 
360  /** \brief flag stating whether the intrinsics matrix has been set or not */
362 
363  /** \brief the transformed intrinsics matrix */
365 
366  /** \brief SVM-based person classifier */
368 
369  /** \brief flag stating if the classifier has been set or not */
371  };
372  } /* namespace people */
373 } /* namespace pcl */
374 #include <pcl/people/impl/ground_based_people_detection_app.hpp>
375 #endif /* PCL_PEOPLE_GROUND_BASED_PEOPLE_DETECTION_APP_H_ */
void setFOV(float min, float max)
Set the field of view of the point cloud in z direction.
GroundBasedPeopleDetectionApp performs people detection on RGB-D data having as input the ground plan...
void getDimensionLimits(int &min_points, int &max_points)
Get minimum and maximum allowed number of points for a person cluster.
void updateMinMaxPoints()
Estimates min_points_ and max_points_ based on the minimal and maximal cluster size and the voxel siz...
PointCloudPtr cloud_filtered_
pointer to the filtered cloud
Eigen::Matrix3f intrinsics_matrix_
intrinsic parameters matrix of the RGB camera
Eigen::VectorXf ground_coeffs_
ground plane coefficients
float heads_minimum_distance_
minimum distance between persons' heads
boost::shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:428
bool compute(std::vector< pcl::people::PersonCluster< PointT > > &clusters)
Perform people detection on the input data and return people clusters information.
Eigen::Matrix3f transformation_
rotation matrix which transforms input point cloud to internal people tracker coordinate frame ...
bool person_classifier_set_flag_
flag stating if the classifier has been set or not
float max_height_
person clusters maximum height from the ground plane
float getMinimumDistanceBetweenHeads()
Get minimum distance between persons' heads.
void setMinimumDistanceBetweenHeads(float heads_minimum_distance)
Set minimum distance between persons' heads.
int sampling_factor_
sampling factor used to downsample the point cloud
float sqrt_ground_coeffs_
ground plane normalization factor
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.
float max_fov_
the end of the field of view in z-direction
void setSamplingFactor(int sampling_factor)
Set sampling factor.
int max_points_
maximum number of points for a person cluster
PointCloudPtr getFilteredCloud()
Get the filtered point cloud.
int min_points_
minimum number of points for a person cluster
bool head_centroid_
if true, the person centroid is computed as the centroid of the cluster points belonging to the head;...
pcl::people::PersonClassifier< pcl::RGB > person_classifier_
SVM-based person classifier.
bool transformation_set_
flag stating whether the transformation matrix has been set or not
float max_width_
person clusters maximum width, used to estimate how many points maximally represent a person cluster ...
float min_height_
person clusters minimum height from the ground plane
float min_fov_
the beginning of the field of view in z-direction, should be usually set to zero
PersonCluster represents a class for representing information about a cluster containing a person...
void applyTransformationGround()
Applies the transformation to the ground plane.
void applyTransformationIntrinsics()
Applies the transformation to the intrinsics matrix.
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...
Eigen::VectorXf getGround()
Get floor coefficients.
void swapDimensions(pcl::PointCloud< pcl::RGB >::Ptr &cloud)
Swap rows/cols dimensions of a RGB point cloud (90 degrees counterclockwise rotation).
void setTransformation(const Eigen::Matrix3f &transformation)
Set the transformation matrix, which is used in order to transform the given point cloud...
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.
boost::shared_ptr< const PointCloud > PointCloudConstPtr
void setInputCloud(PointCloudPtr &cloud)
Set the pointer to the input cloud.
void setClassifier(pcl::people::PersonClassifier< pcl::RGB > person_classifier)
Set SVM-based person classifier.
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 bo...
bool ground_coeffs_set_
flag stating whether the ground coefficients have been set or not
bool vertical_
if true, the sensor is considered to be vertically placed (portrait mode)
Eigen::Matrix3f intrinsics_matrix_transformed_
the transformed intrinsics matrix
float min_width_
person clusters minimum width, used to estimate how many points minimally represent a person cluster ...
PointCloudPtr getNoGroundCloud()
Get pointcloud after voxel grid filtering and ground removal.
void applyTransformationPointCloud()
Applies the transformation to the input point cloud.
bool intrinsics_matrix_set_
flag stating whether the intrinsics matrix has been set or not
Eigen::VectorXf ground_coeffs_transformed_
the transformed ground coefficients
void filter()
Reduces the input cloud to one point per voxel and limits the field of view.
PointCloudPtr no_ground_cloud_
pointer to the cloud after voxel grid filtering and ground removal
void setIntrinsics(Eigen::Matrix3f intrinsics_matrix)
Set intrinsic parameters of the RGB camera.
pcl::PointCloud< pcl::RGB >::Ptr rgb_image_
pointer to a RGB cloud corresponding to cloud_
void setSensorPortraitOrientation(bool vertical)
Set sensor orientation (vertical = true means portrait mode, vertical = false means landscape mode)...