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 #include <boost/thread/thread.hpp>
00037 #include <boost/date_time/posix_time/posix_time.hpp>
00038 #include <pcl/point_cloud.h>
00039 #include <pcl/point_types.h>
00040 #include <pcl/io/openni_grabber.h>
00041 #include <pcl/io/pcd_io.h>
00042 #include <pcl/io/openni_camera/openni_driver.h>
00043 #include <pcl/filters/passthrough.h>
00044 #include <pcl/surface/convex_hull.h>
00045 #include <pcl/console/parse.h>
00046 #include <pcl/common/time.h>
00047 #include <pcl/visualization/cloud_viewer.h>
00048 
00049 using namespace pcl;
00050 using namespace pcl::visualization;
00051 using namespace std;
00052 
00053 #define FPS_CALC(_WHAT_) \
00054 do \
00055 { \
00056     static unsigned count = 0;\
00057     static double last = pcl::getTime ();\
00058     if (++count == 100) \
00059     { \
00060       double now = pcl::getTime (); \
00061       std::cout << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz" <<  std::endl; \
00062       count = 0; \
00063       last = now; \
00064     } \
00065 }while(false)
00066 
00067 template <typename PointType>
00068 class OpenNI3DConvexHull
00069 {
00070   public:
00071     typedef pcl::PointCloud<PointType> Cloud;
00072     typedef typename Cloud::Ptr CloudPtr;
00073     typedef typename Cloud::ConstPtr CloudConstPtr;
00074 
00075     OpenNI3DConvexHull (const std::string& device_id = "")
00076       : viewer ("PCL OpenNI 3D Convex Hull Viewer") 
00077     , device_id_(device_id)
00078     {
00079       pass.setFilterFieldName ("z");
00080       pass.setFilterLimits (0.0, 1.0);
00081     }
00082     
00083     void 
00084     cloud_cb (const CloudConstPtr& cloud)
00085     {
00086       boost::mutex::scoped_lock lock (mtx_);
00087       FPS_CALC ("computation");
00088 
00089       cloud_pass_.reset (new Cloud);
00090       
00091       pass.setInputCloud (cloud);
00092       pass.filter (*cloud_pass_);
00093 
00094       
00095       pcl::ConvexHull<PointType> hr;
00096       hr.setInputCloud (cloud_pass_);
00097       cloud_hull_.reset (new Cloud);
00098       hr.reconstruct (*cloud_hull_, vertices_);
00099 
00100       cloud_ = cloud;
00101       new_cloud_ = true;
00102     }
00103 
00104     void
00105     viz_cb (pcl::visualization::PCLVisualizer& viz)
00106     {
00107       if (!cloud_ || !new_cloud_)
00108       {
00109         boost::this_thread::sleep(boost::posix_time::milliseconds(1));
00110         return;
00111       }
00112 
00113       {
00114         boost::mutex::scoped_lock lock (mtx_);
00115         FPS_CALC ("visualization");
00116         CloudPtr temp_cloud;
00117         temp_cloud.swap (cloud_pass_);
00118 
00119         if (!viz.updatePointCloud (temp_cloud, "OpenNICloud"))
00120         {
00121           viz.addPointCloud (temp_cloud, "OpenNICloud");
00122           viz.resetCameraViewpoint ("OpenNICloud");
00123         }
00124         
00125         if (new_cloud_ && cloud_hull_)
00126         {
00127           viz.removePointCloud ("hull");
00128           viz.addPolygonMesh<PointType> (cloud_hull_, vertices_, "hull");
00129         }
00130         new_cloud_ = false;
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 (&OpenNI3DConvexHull::cloud_cb, this, _1);
00140       boost::signals2::connection c = interface->registerCallback (f);
00141      
00142       viewer.runOnVisualizationThread (boost::bind(&OpenNI3DConvexHull::viz_cb, this, _1), "viz_cb");
00143 
00144       interface->start ();
00145       
00146       while (!viewer.wasStopped ())
00147       {
00148         boost::this_thread::sleep(boost::posix_time::milliseconds(1));
00149       }
00150 
00151       interface->stop ();
00152     }
00153 
00154     pcl::PassThrough<PointType> pass;
00155     pcl::visualization::CloudViewer viewer;
00156 
00157     std::string device_id_;
00158     boost::mutex mtx_;
00159     
00160     CloudConstPtr cloud_;
00161     CloudPtr cloud_pass_, cloud_hull_;
00162     std::vector<pcl::Vertices> vertices_;
00163     bool new_cloud_;
00164 };
00165 
00166 void
00167 usage (char ** argv)
00168 {
00169   std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n";
00170 
00171   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00172   if (driver.getNumberDevices () > 0)
00173   {
00174     for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
00175     {
00176       cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
00177               << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
00178       cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << endl
00179            << "                 bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << endl
00180            << "                 <serial-number> (only in Linux and for devices which provide serial numbers)"  << endl;
00181     }
00182   }
00183   else
00184     cout << "No devices connected." << endl;
00185 }
00186 
00187 int
00188 main (int argc, char ** argv)
00189 {
00190   std::string arg;
00191   if (argc > 1)
00192     arg = std::string (argv[1]);
00193   
00194   if (arg == "--help" || arg == "-h")
00195   {
00196     usage (argv);
00197     return 1;
00198   }
00199 
00200   pcl::OpenNIGrabber grabber ("");
00201   if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba> ())
00202   {
00203     PCL_INFO ("PointXYZRGBA mode enabled.\n");
00204     OpenNI3DConvexHull<pcl::PointXYZRGBA> v ("");
00205     v.run ();
00206   }
00207   else
00208   {
00209     PCL_INFO ("PointXYZ mode enabled.\n");
00210     OpenNI3DConvexHull<pcl::PointXYZ> v ("");
00211     v.run ();
00212   }
00213   return (0);
00214 }