main_ground_based_people_detection.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Point Cloud Library (PCL) - www.pointclouds.org
00005  * Copyright (c) 2013-, Open Perception, Inc.
00006  *
00007  * All rights reserved.
00008  *
00009  * Redistribution and use in source and binary forms, with or without
00010  * modification, are permitted provided that the following conditions
00011  * are met:
00012  *
00013  * * Redistributions of source code must retain the above copyright
00014  * notice, this list of conditions and the following disclaimer.
00015  * * Redistributions in binary form must reproduce the above
00016  * copyright notice, this list of conditions and the following
00017  * disclaimer in the documentation and/or other materials provided
00018  * with the distribution.
00019  * * Neither the name of the copyright holder(s) nor the names of its
00020  * contributors may be used to endorse or promote products derived
00021  * from this software without specific prior written permission.
00022  *
00023  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  * POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * main_ground_based_people_detection_app.cpp
00037  * Created on: Nov 30, 2012
00038  * Author: Matteo Munaro
00039  *
00040  * Example file for performing people detection on a Kinect live stream.
00041  * As a first step, the ground is manually initialized, then people detection is performed with the GroundBasedPeopleDetectionApp class,
00042  * which implements the people detection algorithm described here:
00043  * M. Munaro, F. Basso and E. Menegatti,
00044  * Tracking people within groups with RGB-D data,
00045  * In Proceedings of the International Conference on Intelligent Robots and Systems (IROS) 2012, Vilamoura (Portugal), 2012.
00046  */
00047   
00048 #include <pcl/console/parse.h>
00049 #include <pcl/point_types.h>
00050 #include <pcl/visualization/pcl_visualizer.h>    
00051 #include <pcl/io/openni_grabber.h>
00052 #include <pcl/sample_consensus/sac_model_plane.h>
00053 #include <pcl/people/ground_based_people_detection_app.h>
00054 #include <pcl/common/time.h>
00055 
00056 typedef pcl::PointXYZRGBA PointT;
00057 typedef pcl::PointCloud<PointT> PointCloudT;
00058 
00059 // PCL viewer //
00060 pcl::visualization::PCLVisualizer viewer("PCL Viewer");
00061 
00062 // Mutex: //
00063 boost::mutex cloud_mutex;
00064 
00065 enum { COLS = 640, ROWS = 480 };
00066 
00067 int print_help()
00068 {
00069   cout << "*******************************************************" << std::endl;
00070   cout << "Ground based people detection app options:" << std::endl;
00071   cout << "   --help    <show_this_help>" << std::endl;
00072   cout << "   --svm     <path_to_svm_file>" << std::endl;
00073   cout << "   --conf    <minimum_HOG_confidence (default = -1.5)>" << std::endl;
00074   cout << "   --min_h   <minimum_person_height (default = 1.3)>" << std::endl;
00075   cout << "   --max_h   <maximum_person_height (default = 2.3)>" << std::endl;
00076   cout << "   --sample  <sampling_factor (default = 1)>" << std::endl;
00077   cout << "*******************************************************" << std::endl;
00078   return 0;
00079 }
00080 
00081 void cloud_cb_ (const PointCloudT::ConstPtr &callback_cloud, PointCloudT::Ptr& cloud,
00082     bool* new_cloud_available_flag)
00083 {
00084   cloud_mutex.lock ();    // for not overwriting the point cloud from another thread
00085   *cloud = *callback_cloud;
00086   *new_cloud_available_flag = true;
00087   cloud_mutex.unlock ();
00088 }
00089 
00090 struct callback_args{
00091   // structure used to pass arguments to the callback function
00092   PointCloudT::Ptr clicked_points_3d;
00093   pcl::visualization::PCLVisualizer::Ptr viewerPtr;
00094 };
00095   
00096 void
00097 pp_callback (const pcl::visualization::PointPickingEvent& event, void* args)
00098 {
00099   struct callback_args* data = (struct callback_args *)args;
00100   if (event.getPointIndex () == -1)
00101     return;
00102   PointT current_point;
00103   event.getPoint(current_point.x, current_point.y, current_point.z);
00104   data->clicked_points_3d->points.push_back(current_point);
00105   // Draw clicked points in red:
00106   pcl::visualization::PointCloudColorHandlerCustom<PointT> red (data->clicked_points_3d, 255, 0, 0);
00107   data->viewerPtr->removePointCloud("clicked_points");
00108   data->viewerPtr->addPointCloud(data->clicked_points_3d, red, "clicked_points");
00109   data->viewerPtr->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 10, "clicked_points");
00110   std::cout << current_point.x << " " << current_point.y << " " << current_point.z << std::endl;
00111 }
00112 
00113 int main (int argc, char** argv)
00114 {
00115   if(pcl::console::find_switch (argc, argv, "--help") || pcl::console::find_switch (argc, argv, "-h"))
00116         return print_help();
00117 
00118   // Algorithm parameters:
00119   std::string svm_filename = "../../people/data/trainedLinearSVMForPeopleDetectionWithHOG.yaml";
00120   float min_confidence = -1.5;
00121   float min_height = 1.3;
00122   float max_height = 2.3;
00123   float voxel_size = 0.06;
00124   float sampling_factor = 1;
00125   Eigen::Matrix3f rgb_intrinsics_matrix;
00126   rgb_intrinsics_matrix << 525, 0.0, 319.5, 0.0, 525, 239.5, 0.0, 0.0, 1.0; // Kinect RGB camera intrinsics
00127 
00128   // Read if some parameters are passed from command line:
00129   pcl::console::parse_argument (argc, argv, "--svm", svm_filename);
00130   pcl::console::parse_argument (argc, argv, "--conf", min_confidence);
00131   pcl::console::parse_argument (argc, argv, "--min_h", min_height);
00132   pcl::console::parse_argument (argc, argv, "--max_h", max_height);
00133   pcl::console::parse_argument (argc, argv, "--sample", sampling_factor);
00134 
00135   // Read Kinect live stream:
00136   PointCloudT::Ptr cloud (new PointCloudT);
00137   bool new_cloud_available_flag = false;
00138   pcl::Grabber* interface = new pcl::OpenNIGrabber();
00139   boost::function<void (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr&)> f =
00140       boost::bind (&cloud_cb_, _1, cloud, &new_cloud_available_flag);
00141   interface->registerCallback (f);
00142   interface->start ();
00143 
00144   // Wait for the first frame:
00145   while(!new_cloud_available_flag) 
00146     boost::this_thread::sleep(boost::posix_time::milliseconds(1));
00147   new_cloud_available_flag = false;
00148 
00149   cloud_mutex.lock ();    // for not overwriting the point cloud
00150 
00151   // Display pointcloud:
00152   pcl::visualization::PointCloudColorHandlerRGBField<PointT> rgb(cloud);
00153   viewer.addPointCloud<PointT> (cloud, rgb, "input_cloud");
00154   viewer.setCameraPosition(0,0,-2,0,-1,0,0);
00155 
00156   // Add point picking callback to viewer:
00157   struct callback_args cb_args;
00158   PointCloudT::Ptr clicked_points_3d (new PointCloudT);
00159   cb_args.clicked_points_3d = clicked_points_3d;
00160   cb_args.viewerPtr = pcl::visualization::PCLVisualizer::Ptr(&viewer);
00161   viewer.registerPointPickingCallback (pp_callback, (void*)&cb_args);
00162   std::cout << "Shift+click on three floor points, then press 'Q'..." << std::endl;
00163 
00164   // Spin until 'Q' is pressed:
00165   viewer.spin();
00166   std::cout << "done." << std::endl;
00167   
00168   cloud_mutex.unlock ();    
00169 
00170   // Ground plane estimation:
00171   Eigen::VectorXf ground_coeffs;
00172   ground_coeffs.resize(4);
00173   std::vector<int> clicked_points_indices;
00174   for (unsigned int i = 0; i < clicked_points_3d->points.size(); i++)
00175     clicked_points_indices.push_back(i);
00176   pcl::SampleConsensusModelPlane<PointT> model_plane(clicked_points_3d);
00177   model_plane.computeModelCoefficients(clicked_points_indices,ground_coeffs);
00178   std::cout << "Ground plane: " << ground_coeffs(0) << " " << ground_coeffs(1) << " " << ground_coeffs(2) << " " << ground_coeffs(3) << std::endl;
00179 
00180   // Initialize new viewer:
00181   pcl::visualization::PCLVisualizer viewer("PCL Viewer");          // viewer initialization
00182   viewer.setCameraPosition(0,0,-2,0,-1,0,0);
00183 
00184   // Create classifier for people detection:  
00185   pcl::people::PersonClassifier<pcl::RGB> person_classifier;
00186   person_classifier.loadSVMFromFile(svm_filename);   // load trained SVM
00187 
00188   // People detection app initialization:
00189   pcl::people::GroundBasedPeopleDetectionApp<PointT> people_detector;    // people detection object
00190   people_detector.setVoxelSize(voxel_size);                        // set the voxel size
00191   people_detector.setIntrinsics(rgb_intrinsics_matrix);            // set RGB camera intrinsic parameters
00192   people_detector.setClassifier(person_classifier);                // set person classifier
00193   people_detector.setHeightLimits(min_height, max_height);         // set person classifier
00194   people_detector.setSamplingFactor(sampling_factor);              // set a downsampling factor to the point cloud (for increasing speed)
00195 //  people_detector.setSensorPortraitOrientation(true);              // set sensor orientation to vertical
00196 
00197   // For timing:
00198   static unsigned count = 0;
00199   static double last = pcl::getTime ();
00200 
00201   // Main loop:
00202   while (!viewer.wasStopped())
00203   {
00204     if (new_cloud_available_flag && cloud_mutex.try_lock ())    // if a new cloud is available
00205     {
00206       new_cloud_available_flag = false;
00207 
00208       // Perform people detection on the new cloud:
00209       std::vector<pcl::people::PersonCluster<PointT> > clusters;   // vector containing persons clusters
00210       people_detector.setInputCloud(cloud);
00211       people_detector.setGround(ground_coeffs);                    // set floor coefficients
00212       people_detector.compute(clusters);                           // perform people detection
00213 
00214       ground_coeffs = people_detector.getGround();                 // get updated floor coefficients
00215 
00216       // Draw cloud and people bounding boxes in the viewer:
00217       viewer.removeAllPointClouds();
00218       viewer.removeAllShapes();
00219       pcl::visualization::PointCloudColorHandlerRGBField<PointT> rgb(cloud);
00220       viewer.addPointCloud<PointT> (cloud, rgb, "input_cloud");
00221       unsigned int k = 0;
00222       for(std::vector<pcl::people::PersonCluster<PointT> >::iterator it = clusters.begin(); it != clusters.end(); ++it)
00223       {
00224         if(it->getPersonConfidence() > min_confidence)             // draw only people with confidence above a threshold
00225         {
00226           // draw theoretical person bounding box in the PCL viewer:
00227           it->drawTBoundingBox(viewer, k);
00228           k++;
00229         }
00230       }
00231       std::cout << k << " people found" << std::endl;
00232       viewer.spinOnce();
00233 
00234       // Display average framerate:
00235       if (++count == 30)
00236       {
00237         double now = pcl::getTime ();
00238         std::cout << "Average framerate: " << double(count)/double(now - last) << " Hz" <<  std::endl;
00239         count = 0;
00240         last = now;
00241       }
00242       cloud_mutex.unlock ();
00243     }
00244   }
00245 
00246   return 0;
00247 }
00248 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:25:20