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 #define SHOW_FPS 1
00041 #include <pcl/apps/timer.h>
00042 #include <pcl/common/common.h>
00043 #include <pcl/common/angles.h>
00044 #include <pcl/common/time.h>
00045 #include <pcl/io/openni_grabber.h>
00046 #include <pcl/io/pcd_io.h>
00047 #include <pcl/keypoints/agast_2d.h>
00048 #include <pcl/filters/extract_indices.h>
00049 #include <pcl/visualization/pcl_visualizer.h>
00050 #include <pcl/visualization/image_viewer.h>
00051 #include <pcl/console/print.h>
00052 #include <pcl/console/parse.h>
00053 
00054 using namespace pcl;
00055 using namespace std;
00056 
00057 typedef PointUV KeyPointT;
00058 
00060 template <typename PointT>
00061 class AGASTDemo
00062 {
00063   public:
00064     typedef PointCloud<PointT> Cloud;
00065     typedef typename Cloud::Ptr CloudPtr;
00066     typedef typename Cloud::ConstPtr CloudConstPtr;
00067 
00068     AGASTDemo (Grabber& grabber)
00069       : cloud_viewer_ ("AGAST 2D Keypoints -- PointCloud")
00070       , grabber_ (grabber)
00071       , image_viewer_ ("AGAST 2D Keypoints -- Image")
00072       , bmax_ (255)
00073       , threshold_ (30)
00074       , detector_type_ (0)
00075       , timer_ ()
00076     {
00077     }
00078 
00080     void
00081     cloud_callback (const CloudConstPtr& cloud)
00082     {
00083       FPS_CALC ("cloud callback");
00084       boost::mutex::scoped_lock lock (cloud_mutex_);
00085 
00086       
00087       AgastKeypoint2D<PointT> agast;
00088       agast.setNonMaxSuppression (true);
00089       agast.setThreshold (threshold_);
00090       agast.setMaxDataValue (bmax_);
00091       agast.setInputCloud (cloud);
00092 
00093       keypoints_.reset (new PointCloud<KeyPointT>);
00094 
00095       
00096       switch (detector_type_)
00097       {
00098         case 1:
00099         default:
00100         {
00101           timer_.reset ();
00102           pcl::keypoints::agast::AgastDetector7_12s::Ptr detector (new pcl::keypoints::agast::AgastDetector7_12s (cloud->width, cloud->height, threshold_, bmax_));
00103           agast.setAgastDetector (detector);
00104           agast.compute (*keypoints_);
00105           PCL_DEBUG ("AGAST 7_12s computation took %f ms.\n", timer_.getTime ());
00106           break;
00107         }
00108         case 2:
00109         {
00110           timer_.reset ();
00111           pcl::keypoints::agast::AgastDetector5_8::Ptr detector (new pcl::keypoints::agast::AgastDetector5_8 (cloud->width, cloud->height, threshold_, bmax_));
00112           agast.setAgastDetector (detector);
00113           agast.compute (*keypoints_);
00114           PCL_DEBUG ("AGAST 5_8 computation took %f ms.\n", timer_.getTime ());
00115           break;
00116         }
00117         case 3:
00118         {
00119           timer_.reset ();
00120           pcl::keypoints::agast::OastDetector9_16::Ptr detector (new pcl::keypoints::agast::OastDetector9_16 (cloud->width, cloud->height, threshold_, bmax_));
00121           agast.setAgastDetector (detector);
00122           agast.compute (*keypoints_);
00123           PCL_DEBUG ("OAST 9_6 computation took %f ms.\n", timer_.getTime ());
00124           break;
00125         }
00126       }
00127       cloud_ = cloud;
00128     }
00129 
00131     void 
00132     keyboard_callback (const pcl::visualization::KeyboardEvent& event, void* cookie)
00133     {
00134       AGASTDemo* obj = static_cast<AGASTDemo*> (cookie);
00135       
00136       if (event.getKeyCode ())
00137       {
00138         std::stringstream ss; ss << event.getKeyCode ();
00139         obj->detector_type_ = atoi (ss.str ().c_str ());
00140         return;
00141       }
00142 
00143       if (event.getKeySym () == "Up")
00144       {
00145         if (obj->threshold_ <= 0.9)
00146         {
00147           PCL_INFO ("[keyboard_callback] Increase AGAST threshold from %f to %f.\n", obj->threshold_, obj->threshold_ + 0.01);
00148           obj->threshold_ += 0.01;
00149           return;
00150         }
00151         PCL_INFO ("[keyboard_callback] Increase AGAST threshold from %f to %f.\n", obj->threshold_, obj->threshold_ + 1);
00152         obj->threshold_ += 1;
00153         return;
00154       }
00155 
00156       if (event.getKeySym () == "Down")
00157       {
00158         if (obj->threshold_ <= 0)
00159           return;
00160         if (obj->threshold_ <= 1)
00161         {
00162           PCL_INFO ("[keyboard_callback] Decrease AGAST threshold from %f to %f.\n", obj->threshold_, obj->threshold_ - 0.01);
00163           obj->threshold_ -= 0.01;
00164           return;
00165         }
00166         PCL_INFO ("[keyboard_callback] Decrease AGAST threshold from %f to %f.\n", obj->threshold_, obj->threshold_ - 1);
00167         obj->threshold_ -= 1;
00168         return;
00169       }
00170 
00171       if (event.getKeySym () == "Right")
00172       {
00173         PCL_INFO ("[keyboard_callback] Increase AGAST BMAX from %f to %f.\n", obj->bmax_, obj->bmax_ + 1);
00174         obj->bmax_ += 1;
00175         return;
00176       }
00177 
00178       if (event.getKeySym () == "Left")
00179       {
00180         if (obj->bmax_ <= 0)
00181           return;
00182         PCL_INFO ("[keyboard_callback] Decrease AGAST BMAX from %f to %f.\n", obj->bmax_, obj->bmax_ - 1);
00183         obj->bmax_ -= 1;
00184         return;
00185       }
00186     }
00187 
00189     void
00190     init ()
00191     {
00192       boost::function<void (const CloudConstPtr&) > cloud_cb = boost::bind (&AGASTDemo::cloud_callback, this, _1);
00193       cloud_connection = grabber_.registerCallback (cloud_cb);      
00194     }
00195 
00197     string
00198     getStrBool (bool state)
00199     {
00200       stringstream ss;
00201       ss << state;
00202       return (ss.str ());
00203     }
00204 
00206     void
00207     get3DKeypoints (
00208         const CloudConstPtr &cloud,
00209         const PointCloud<KeyPointT>::Ptr &keypoints, PointCloud<PointT> &keypoints3d)
00210     {
00211       if (!cloud || !keypoints || cloud->points.empty () || keypoints->points.empty ())
00212         return;
00213 
00214       keypoints3d.resize (keypoints->size ());
00215       keypoints3d.width = keypoints->width;
00216       keypoints3d.height = keypoints->height;
00217       keypoints3d.is_dense = true;
00218 
00219       int j = 0;
00220       for (size_t i = 0; i < keypoints->size (); ++i)
00221       {
00222         const PointT &pt = (*cloud)(static_cast<long unsigned int> (keypoints->points[i].u), 
00223                                     static_cast<long unsigned int> (keypoints->points[i].v));
00224         if (!pcl_isfinite (pt.x) || !pcl_isfinite (pt.y) || !pcl_isfinite (pt.z))
00225           continue;
00226 
00227         keypoints3d.points[j].x = pt.x;
00228         keypoints3d.points[j].y = pt.y;
00229         keypoints3d.points[j].z = pt.z;
00230         ++j;
00231       }
00232 
00233       if (j != keypoints->size ())
00234       {
00235         keypoints3d.resize (j);
00236         keypoints3d.width = j;
00237         keypoints3d.height = 1;
00238       }
00239     }
00240     
00242     void
00243     run ()
00244     {
00245       cloud_viewer_.registerKeyboardCallback (&AGASTDemo::keyboard_callback, *this, static_cast<AGASTDemo*> (this));
00246       image_viewer_.registerKeyboardCallback (&AGASTDemo::keyboard_callback, *this, static_cast<AGASTDemo*> (this));
00247 
00248       grabber_.start ();
00249       
00250       bool image_init = false, cloud_init = false;
00251       bool keypts = true;
00252 
00253       CloudPtr keypoints3d (new Cloud);
00254 
00255       while (!cloud_viewer_.wasStopped () && !image_viewer_.wasStopped ())
00256       {
00257         PointCloud<KeyPointT>::Ptr keypoints;
00258         CloudConstPtr cloud;
00259 
00260         if (cloud_mutex_.try_lock ())
00261         {
00262           cloud_.swap (cloud);
00263           keypoints_.swap (keypoints);
00264         
00265           cloud_mutex_.unlock ();
00266         }
00267 
00268         if (cloud)
00269         {
00270           if (!cloud_init)
00271           {
00272             cloud_viewer_.setPosition (0, 0);
00273             cloud_viewer_.setSize (cloud->width, cloud->height);
00274             cloud_init = !cloud_init;
00275           }
00276 
00277           if (!cloud_viewer_.updatePointCloud (cloud, "OpenNICloud"))
00278           {
00279             cloud_viewer_.addPointCloud (cloud, "OpenNICloud");
00280             cloud_viewer_.resetCameraViewpoint ("OpenNICloud");
00281           }
00282 
00283           if (!image_init)
00284           {
00285             image_viewer_.setPosition (cloud->width, 0);
00286             image_viewer_.setSize (cloud->width, cloud->height);
00287             image_init = !image_init;
00288           }
00289 
00290           image_viewer_.addRGBImage<PointT> (cloud);
00291 
00292           if (keypoints && !keypoints->empty ())
00293           {
00294             image_viewer_.removeLayer (getStrBool (keypts));
00295             for (size_t i = 0; i < keypoints->size (); ++i)
00296             {
00297               int u = int (keypoints->points[i].u);
00298               int v = int (keypoints->points[i].v);
00299               image_viewer_.markPoint (u, v, visualization::red_color, visualization::blue_color, 10, getStrBool (!keypts));
00300             }
00301             keypts = !keypts;
00302 
00303             get3DKeypoints (cloud, keypoints, *keypoints3d);
00304             visualization::PointCloudColorHandlerCustom<PointT> blue (keypoints3d, 0, 0, 255);
00305             if (!cloud_viewer_.updatePointCloud (keypoints3d, blue, "keypoints"))
00306               cloud_viewer_.addPointCloud (keypoints3d, blue, "keypoints");
00307             cloud_viewer_.setPointCloudRenderingProperties (visualization::PCL_VISUALIZER_POINT_SIZE, 20, "keypoints");
00308             cloud_viewer_.setPointCloudRenderingProperties (visualization::PCL_VISUALIZER_OPACITY, 0.5, "keypoints");
00309           }
00310         }
00311 
00312         cloud_viewer_.spinOnce ();
00313         image_viewer_.spinOnce ();
00314         boost::this_thread::sleep (boost::posix_time::microseconds (100));
00315       }
00316 
00317       grabber_.stop ();
00318       cloud_connection.disconnect ();
00319     }
00320     
00321     visualization::PCLVisualizer cloud_viewer_;
00322     Grabber& grabber_;
00323     boost::mutex cloud_mutex_;
00324     CloudConstPtr cloud_;
00325     
00326     visualization::ImageViewer image_viewer_;
00327 
00328     PointCloud<KeyPointT>::Ptr keypoints_;
00329 
00330     double bmax_;
00331     double threshold_;
00332     int detector_type_;
00333   private:
00334     boost::signals2::connection cloud_connection;
00335     StopWatch timer_;
00336 };
00337 
00338 
00339 int
00340 main (int argc, char** argv)
00341 {
00342   bool debug = false;
00343   pcl::console::parse_argument (argc, argv, "-debug", debug);
00344   if (debug)
00345     pcl::console::setVerbosityLevel (pcl::console::L_DEBUG);
00346   else
00347     pcl::console::setVerbosityLevel (pcl::console::L_INFO);
00348 
00349   string device_id ("#1");
00350   OpenNIGrabber grabber (device_id);
00351   AGASTDemo<PointXYZRGBA> openni_viewer (grabber);
00352 
00353   openni_viewer.init ();
00354   openni_viewer.run ();
00355   
00356   return (0);
00357 }
00358