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