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 #include <pcl/point_cloud.h>
00037 #include <pcl/point_types.h>
00038 #include <pcl/io/openni_grabber.h>
00039 #include <pcl/visualization/cloud_viewer.h>
00040 #include <pcl/io/openni_camera/openni_driver.h>
00041 #include <pcl/console/parse.h>
00042 #include <pcl/common/time.h>
00043 #include <pcl/surface/mls.h>
00044 #include <pcl/kdtree/kdtree_flann.h>
00045 
00046 #define FPS_CALC(_WHAT_) \
00047 do \
00048 { \
00049     static unsigned count = 0;\
00050     static double last = pcl::getTime ();\
00051     double now = pcl::getTime (); \
00052     ++count; \
00053     if (now - last >= 1.0) \
00054     { \
00055       std::cout << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz" <<  std::endl; \
00056       count = 0; \
00057       last = now; \
00058       if (*stop_computing_) std::cout << "Press 's' to start computing!\n"; \
00059     } \
00060 }while(false)
00061 
00062 
00063 int default_polynomial_order = 2;
00064 bool default_use_polynomial_fit = false;
00065 double default_search_radius = 0.0,
00066     default_sqr_gauss_param = 0.0;
00067 
00068 template <typename PointType>
00069 class OpenNISmoothing;
00070 
00071 
00072 void keyboardEventOccurred (const pcl::visualization::KeyboardEvent &event,
00073                             void *stop_void)
00074 {
00075   boost::shared_ptr<bool> stop = *static_cast<boost::shared_ptr<bool>*> (stop_void);
00076   if (event.getKeySym () == "s" && event.keyDown ())
00077   {
00078     *stop = ! *stop;
00079     if (*stop) std::cout << "Computing is now stopped!\n";
00080     else std::cout << "Computing commencing!\n";
00081   }
00082 }
00083 
00084 template <typename PointType>
00085 class OpenNISmoothing
00086 {
00087   public:
00088     typedef pcl::PointCloud<PointType> Cloud;
00089     typedef typename Cloud::Ptr CloudPtr;
00090     typedef typename Cloud::ConstPtr CloudConstPtr;
00091 
00092     OpenNISmoothing (double search_radius, bool sqr_gauss_param_set, double sqr_gauss_param,
00093                      bool use_polynomial_fit, int polynomial_order,
00094                      const std::string& device_id = "")
00095     : viewer ("PCL OpenNI MLS Smoothing")
00096     , device_id_(device_id)
00097     {
00098       
00099       smoother_.setSearchRadius (search_radius);
00100       if (sqr_gauss_param_set) smoother_.setSqrGaussParam (sqr_gauss_param);
00101       smoother_.setPolynomialFit (use_polynomial_fit);
00102       smoother_.setPolynomialOrder (polynomial_order);
00103 
00104       typename pcl::search::KdTree<PointType>::Ptr tree (new typename pcl::search::KdTree<PointType> ());
00105       smoother_.setSearchMethod (tree);
00106 
00107       viewer.createViewPort (0.0, 0.0, 0.5, 1.0, viewport_input_);
00108       viewer.setBackgroundColor (0, 0, 0, viewport_input_);
00109       viewer.createViewPort (0.5, 0.0, 1.0, 1.0, viewport_smoothed_);
00110       viewer.setBackgroundColor (0, 0, 0, viewport_smoothed_);
00111 
00112       stop_computing_.reset (new bool(true));
00113       cloud_.reset ();
00114       cloud_smoothed_.reset (new Cloud);
00115     }
00116 
00117     void
00118     cloud_cb_ (const CloudConstPtr& cloud)
00119     {
00120       FPS_CALC ("computation");
00121 
00122       mtx_.lock ();
00123       if (! *stop_computing_)
00124       {
00125         smoother_.setInputCloud (cloud);
00126         smoother_.process (*cloud_smoothed_);
00127       }
00128       cloud_ = cloud;
00129       mtx_.unlock ();
00130     }
00131 
00132 
00133 
00134     void
00135     run ()
00136     {
00137       pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_);
00138 
00139       boost::function<void (const CloudConstPtr&)> f = boost::bind (&OpenNISmoothing::cloud_cb_, this, _1);
00140       boost::signals2::connection c = interface->registerCallback (f);
00141 
00142       viewer.registerKeyboardCallback (keyboardEventOccurred, reinterpret_cast<void*> (&stop_computing_));
00143 
00144 
00145       interface->start ();
00146 
00147       while (!viewer.wasStopped ())
00148       {
00149         FPS_CALC ("visualization");
00150         viewer.spinOnce ();
00151 
00152         if (cloud_ && mtx_.try_lock ())
00153         {
00154           if (!viewer.updatePointCloud (cloud_, "input_cloud"))
00155             viewer.addPointCloud (cloud_, "input_cloud", viewport_input_);
00156           if (! *stop_computing_ && !viewer.updatePointCloud (cloud_smoothed_, "smoothed_cloud"))
00157             viewer.addPointCloud (cloud_smoothed_, "smoothed_cloud", viewport_smoothed_);
00158           mtx_.unlock ();
00159         }
00160       }
00161 
00162       interface->stop ();
00163     }
00164 
00165     pcl::MovingLeastSquares<PointType, PointType> smoother_;
00166     pcl::visualization::PCLVisualizer viewer;
00167     std::string device_id_;
00168     boost::mutex mtx_;
00169     CloudConstPtr cloud_;
00170     CloudPtr cloud_smoothed_;
00171     int viewport_input_, viewport_smoothed_;
00172     boost::shared_ptr<bool> stop_computing_;
00173 };
00174 
00175 void
00176 usage (char ** argv)
00177 {
00178   std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n"
00179             << "where options are:\n"
00180             << "                     -search_radius X = sphere radius to be used for finding the k-nearest neighbors used for fitting (default: " << default_search_radius << ")\n"
00181             << "                     -sqr_gauss_param X = parameter used for the distance based weighting of neighbors (recommended = search_radius^2) (default: " << default_sqr_gauss_param << ")\n"
00182             << "                     -use_polynomial_fit X = decides whether the surface and normal are approximated using a polynomial or only via tangent estimation (default: " << default_use_polynomial_fit << ")\n"
00183             << "                     -polynomial_order X = order of the polynomial to be fit (implicitly, use_polynomial_fit = 1) (default: " << default_polynomial_order << ")\n";
00184 
00185   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00186   if (driver.getNumberDevices () > 0)
00187   {
00188     for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
00189     {
00190       cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
00191               << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
00192       cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << endl
00193            << "                 bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << endl
00194            << "                 <serial-number> (only in Linux and for devices which provide serial numbers)"  << endl;
00195     }
00196   }
00197   else
00198     cout << "No devices connected." << endl;
00199 }
00200 
00201 int
00202 main (int argc, char ** argv)
00203 {
00204   if (argc < 2)
00205   {
00206     usage (argv);
00207     return 1;
00208   }
00209 
00210   std::string arg (argv[1]);
00211 
00212   if (arg == "--help" || arg == "-h")
00213   {
00214     usage (argv);
00215     return 1;
00216   }
00217 
00218   
00219   double search_radius = default_search_radius;
00220   double sqr_gauss_param = default_sqr_gauss_param;
00221   bool sqr_gauss_param_set = true;
00222   int polynomial_order = default_polynomial_order;
00223   bool use_polynomial_fit = default_use_polynomial_fit;
00224 
00225   pcl::console::parse_argument (argc, argv, "-search_radius", search_radius);
00226   if (pcl::console::parse_argument (argc, argv, "-sqr_gauss_param", sqr_gauss_param) == -1)
00227     sqr_gauss_param_set = false;
00228   if (pcl::console::parse_argument (argc, argv, "-polynomial_order", polynomial_order) == -1 )
00229     use_polynomial_fit = true;
00230   pcl::console::parse_argument (argc, argv, "-use_polynomial_fit", use_polynomial_fit);
00231 
00232   pcl::OpenNIGrabber grabber (arg);
00233   if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba> ())
00234   {
00235     OpenNISmoothing<pcl::PointXYZRGBA> v (search_radius, sqr_gauss_param_set, sqr_gauss_param, 
00236                                           use_polynomial_fit, polynomial_order, arg);
00237     v.run ();
00238   }
00239   else
00240   {
00241     OpenNISmoothing<pcl::PointXYZ> v (search_radius, sqr_gauss_param_set, sqr_gauss_param,
00242                                       use_polynomial_fit, polynomial_order, arg);
00243     v.run ();
00244   }
00245 
00246   return (0);
00247 }