Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041 #ifndef PCL_PEOPLE_HEAD_BASED_SUBCLUSTER_HPP_
00042 #define PCL_PEOPLE_HEAD_BASED_SUBCLUSTER_HPP_
00043
00044 #include <pcl/people/head_based_subcluster.h>
00045
00046 template <typename PointT>
00047 pcl::people::HeadBasedSubclustering<PointT>::HeadBasedSubclustering ()
00048 {
00049
00050 vertical_ = false;
00051 head_centroid_ = true;
00052 min_height_ = 1.3;
00053 max_height_ = 2.3;
00054 min_points_ = 30;
00055 max_points_ = 5000;
00056 heads_minimum_distance_ = 0.3;
00057
00058
00059 sqrt_ground_coeffs_ = std::numeric_limits<float>::quiet_NaN();
00060 }
00061
00062 template <typename PointT> void
00063 pcl::people::HeadBasedSubclustering<PointT>::setInputCloud (PointCloudPtr& cloud)
00064 {
00065 cloud_ = cloud;
00066 }
00067
00068 template <typename PointT> void
00069 pcl::people::HeadBasedSubclustering<PointT>::setGround (Eigen::VectorXf& ground_coeffs)
00070 {
00071 ground_coeffs_ = ground_coeffs;
00072 sqrt_ground_coeffs_ = (ground_coeffs - Eigen::Vector4f(0.0f, 0.0f, 0.0f, ground_coeffs(3))).norm();
00073 }
00074
00075 template <typename PointT> void
00076 pcl::people::HeadBasedSubclustering<PointT>::setInitialClusters (std::vector<pcl::PointIndices>& cluster_indices)
00077 {
00078 cluster_indices_ = cluster_indices;
00079 }
00080
00081 template <typename PointT> void
00082 pcl::people::HeadBasedSubclustering<PointT>::setSensorPortraitOrientation (bool vertical)
00083 {
00084 vertical_ = vertical;
00085 }
00086
00087 template <typename PointT> void
00088 pcl::people::HeadBasedSubclustering<PointT>::setHeightLimits (float min_height, float max_height)
00089 {
00090 min_height_ = min_height;
00091 max_height_ = max_height;
00092 }
00093
00094 template <typename PointT> void
00095 pcl::people::HeadBasedSubclustering<PointT>::setDimensionLimits (int min_points, int max_points)
00096 {
00097 min_points_ = min_points;
00098 max_points_ = max_points;
00099 }
00100
00101 template <typename PointT> void
00102 pcl::people::HeadBasedSubclustering<PointT>::setMinimumDistanceBetweenHeads (float heads_minimum_distance)
00103 {
00104 heads_minimum_distance_= heads_minimum_distance;
00105 }
00106
00107 template <typename PointT> void
00108 pcl::people::HeadBasedSubclustering<PointT>::setHeadCentroid (bool head_centroid)
00109 {
00110 head_centroid_ = head_centroid;
00111 }
00112
00113 template <typename PointT> void
00114 pcl::people::HeadBasedSubclustering<PointT>::getHeightLimits (float& min_height, float& max_height)
00115 {
00116 min_height = min_height_;
00117 max_height = max_height_;
00118 }
00119
00120 template <typename PointT> void
00121 pcl::people::HeadBasedSubclustering<PointT>::getDimensionLimits (int& min_points, int& max_points)
00122 {
00123 min_points = min_points_;
00124 max_points = max_points_;
00125 }
00126
00127 template <typename PointT> float
00128 pcl::people::HeadBasedSubclustering<PointT>::getMinimumDistanceBetweenHeads ()
00129 {
00130 return (heads_minimum_distance_);
00131 }
00132
00133 template <typename PointT> void
00134 pcl::people::HeadBasedSubclustering<PointT>::mergeClustersCloseInFloorCoordinates (std::vector<pcl::people::PersonCluster<PointT> >& input_clusters,
00135 std::vector<pcl::people::PersonCluster<PointT> >& output_clusters)
00136 {
00137 float min_distance_between_cluster_centers = 0.4;
00138 float normalize_factor = std::pow(sqrt_ground_coeffs_, 2);
00139 Eigen::Vector3f head_ground_coeffs = ground_coeffs_.head(3);
00140 std::vector <std::vector<int> > connected_clusters;
00141 connected_clusters.resize(input_clusters.size());
00142 std::vector<bool> used_clusters;
00143 used_clusters.resize(input_clusters.size());
00144 for(unsigned int i = 0; i < input_clusters.size(); i++)
00145 {
00146 Eigen::Vector3f theoretical_center = input_clusters[i].getTCenter();
00147 float t = theoretical_center.dot(head_ground_coeffs) / normalize_factor;
00148 Eigen::Vector3f current_cluster_center_projection = theoretical_center - head_ground_coeffs * t;
00149 for(unsigned int j = i+1; j < input_clusters.size(); j++)
00150 {
00151 theoretical_center = input_clusters[j].getTCenter();
00152 float t = theoretical_center.dot(head_ground_coeffs) / normalize_factor;
00153 Eigen::Vector3f new_cluster_center_projection = theoretical_center - head_ground_coeffs * t;
00154 if (((new_cluster_center_projection - current_cluster_center_projection).norm()) < min_distance_between_cluster_centers)
00155 {
00156 connected_clusters[i].push_back(j);
00157 }
00158 }
00159 }
00160
00161 for(unsigned int i = 0; i < connected_clusters.size(); i++)
00162 {
00163 if (!used_clusters[i])
00164 {
00165 used_clusters[i] = true;
00166 if (connected_clusters[i].empty())
00167 {
00168 output_clusters.push_back(input_clusters[i]);
00169 }
00170 else
00171 {
00172
00173 pcl::PointIndices point_indices;
00174 point_indices = input_clusters[i].getIndices();
00175 for(unsigned int j = 0; j < connected_clusters[i].size(); j++)
00176 {
00177 if (!used_clusters[connected_clusters[i][j]])
00178 {
00179 used_clusters[connected_clusters[i][j]] = true;
00180 for(std::vector<int>::const_iterator points_iterator = input_clusters[connected_clusters[i][j]].getIndices().indices.begin();
00181 points_iterator != input_clusters[connected_clusters[i][j]].getIndices().indices.end(); points_iterator++)
00182 {
00183 point_indices.indices.push_back(*points_iterator);
00184 }
00185 }
00186 }
00187 pcl::people::PersonCluster<PointT> cluster(cloud_, point_indices, ground_coeffs_, sqrt_ground_coeffs_, head_centroid_, vertical_);
00188 output_clusters.push_back(cluster);
00189 }
00190 }
00191 }
00192 }
00193
00194 template <typename PointT> void
00195 pcl::people::HeadBasedSubclustering<PointT>::createSubClusters (pcl::people::PersonCluster<PointT>& cluster, int maxima_number,
00196 std::vector<int>& maxima_cloud_indices, std::vector<pcl::people::PersonCluster<PointT> >& subclusters)
00197 {
00198
00199 float normalize_factor = std::pow(sqrt_ground_coeffs_, 2);
00200 Eigen::Vector3f head_ground_coeffs = ground_coeffs_.head(3);
00201 Eigen::Matrix3Xf maxima_projected(3,maxima_number);
00202 Eigen::VectorXi subclusters_number_of_points(maxima_number);
00203 std::vector <std::vector <int> > sub_clusters_indices;
00204 sub_clusters_indices.resize(maxima_number);
00205
00206
00207 for(int i = 0; i < maxima_number; i++)
00208 {
00209 PointT* current_point = &cloud_->points[maxima_cloud_indices[i]];
00210 Eigen::Vector3f p_current_eigen(current_point->x, current_point->y, current_point->z);
00211 float t = p_current_eigen.dot(head_ground_coeffs) / normalize_factor;
00212 maxima_projected.col(i).matrix () = p_current_eigen - head_ground_coeffs * t;
00213 subclusters_number_of_points(i) = 0;
00214 }
00215
00216
00217 for(std::vector<int>::const_iterator points_iterator = cluster.getIndices().indices.begin(); points_iterator != cluster.getIndices().indices.end(); points_iterator++)
00218 {
00219 PointT* current_point = &cloud_->points[*points_iterator];
00220 Eigen::Vector3f p_current_eigen(current_point->x, current_point->y, current_point->z);
00221 float t = p_current_eigen.dot(head_ground_coeffs) / normalize_factor;
00222 p_current_eigen = p_current_eigen - head_ground_coeffs * t;
00223
00224 int i = 0;
00225 bool correspondence_detected = false;
00226 while ((!correspondence_detected) && (i < maxima_number))
00227 {
00228 if (((p_current_eigen - maxima_projected.col(i)).norm()) < heads_minimum_distance_)
00229 {
00230 correspondence_detected = true;
00231 sub_clusters_indices[i].push_back(*points_iterator);
00232 subclusters_number_of_points(i)++;
00233 }
00234 else
00235 i++;
00236 }
00237 }
00238
00239
00240 for(int i = 0; i < maxima_number; i++)
00241 {
00242 if (subclusters_number_of_points(i) > min_points_)
00243 {
00244 pcl::PointIndices point_indices;
00245 point_indices.indices = sub_clusters_indices[i];
00246
00247 pcl::people::PersonCluster<PointT> cluster(cloud_, point_indices, ground_coeffs_, sqrt_ground_coeffs_, head_centroid_, vertical_);
00248 subclusters.push_back(cluster);
00249
00250 }
00251 }
00252 }
00253
00254 template <typename PointT> void
00255 pcl::people::HeadBasedSubclustering<PointT>::subcluster (std::vector<pcl::people::PersonCluster<PointT> >& clusters)
00256 {
00257
00258 if (sqrt_ground_coeffs_ != sqrt_ground_coeffs_)
00259 {
00260 PCL_ERROR ("[pcl::people::pcl::people::HeadBasedSubclustering::subcluster] Floor parameters have not been set or they are not valid!\n");
00261 return;
00262 }
00263 if (cluster_indices_.size() == 0)
00264 {
00265 PCL_ERROR ("[pcl::people::pcl::people::HeadBasedSubclustering::subcluster] Cluster indices have not been set!\n");
00266 return;
00267 }
00268 if (cloud_ == NULL)
00269 {
00270 PCL_ERROR ("[pcl::people::pcl::people::HeadBasedSubclustering::subcluster] Input cloud has not been set!\n");
00271 return;
00272 }
00273
00274
00275 for(std::vector<pcl::PointIndices>::const_iterator it = cluster_indices_.begin(); it != cluster_indices_.end(); ++it)
00276 {
00277 pcl::people::PersonCluster<PointT> cluster(cloud_, *it, ground_coeffs_, sqrt_ground_coeffs_, head_centroid_, vertical_);
00278 clusters.push_back(cluster);
00279 }
00280
00281
00282 std::vector<pcl::people::PersonCluster<PointT> > new_clusters;
00283 for(unsigned int i = 0; i < clusters.size(); i++)
00284 {
00285 if (clusters[i].getHeight() <= max_height_)
00286 new_clusters.push_back(clusters[i]);
00287 }
00288 clusters = new_clusters;
00289 new_clusters.clear();
00290
00291
00292 mergeClustersCloseInFloorCoordinates(clusters, new_clusters);
00293 clusters = new_clusters;
00294
00295 std::vector<pcl::people::PersonCluster<PointT> > subclusters;
00296 int cluster_min_points_sub = int(float(min_points_) * 1.5);
00297
00298
00299
00300 pcl::people::HeightMap2D<PointT> height_map_obj;
00301 height_map_obj.setGround(ground_coeffs_);
00302 height_map_obj.setInputCloud(cloud_);
00303 height_map_obj.setSensorPortraitOrientation(vertical_);
00304 height_map_obj.setMinimumDistanceBetweenMaxima(heads_minimum_distance_);
00305 for(typename std::vector<pcl::people::PersonCluster<PointT> >::iterator it = clusters.begin(); it != clusters.end(); ++it)
00306 {
00307 float height = it->getHeight();
00308 int number_of_points = it->getNumberPoints();
00309 if(height > min_height_ && height < max_height_)
00310 {
00311 if (number_of_points > cluster_min_points_sub)
00312 {
00313
00314 height_map_obj.compute(*it);
00315 if (height_map_obj.getMaximaNumberAfterFiltering() > 1)
00316 {
00317
00318 createSubClusters(*it, height_map_obj.getMaximaNumberAfterFiltering(), height_map_obj.getMaximaCloudIndicesFiltered(), subclusters);
00319 }
00320 else
00321 {
00322 subclusters.push_back(*it);
00323 }
00324 }
00325 else
00326 {
00327
00328 subclusters.push_back(*it);
00329 }
00330 }
00331 }
00332 clusters = subclusters;
00333 }
00334
00335 template <typename PointT>
00336 pcl::people::HeadBasedSubclustering<PointT>::~HeadBasedSubclustering ()
00337 {
00338
00339 }
00340 #endif