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/surface/organized_fast_mesh.h>
00044 #include <pcl/console/parse.h>
00045 #include <pcl/common/time.h>
00046 #include <pcl/console/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 OpenNIFastMesh
00069 {
00070 public:
00071 typedef pcl::PointCloud<PointType> Cloud;
00072 typedef typename Cloud::Ptr CloudPtr;
00073 typedef typename Cloud::ConstPtr CloudConstPtr;
00074
00075 OpenNIFastMesh (const std::string& device_id = "")
00076 : device_id_(device_id), vertices_ ()
00077 {
00078 ofm.setTrianglePixelSize (3);
00079 ofm.setTriangulationType (pcl::OrganizedFastMesh<PointType>::QUAD_MESH);
00080 }
00081
00082 void
00083 cloud_cb (const CloudConstPtr& cloud)
00084 {
00085
00086 FPS_CALC ("computation");
00087
00088
00089 ofm.setInputCloud (cloud);
00090
00091
00092 boost::shared_ptr<std::vector<pcl::Vertices> > temp_verts (new std::vector<pcl::Vertices>);
00093 ofm.reconstruct (*temp_verts);
00094
00095
00096 {
00097 boost::mutex::scoped_lock lock (mtx_);
00098
00099
00100
00101
00102
00103 vertices_= temp_verts;
00104 cloud_ = cloud;
00105 }
00106 }
00107
00108 void
00109 run (int argc, char **argv)
00110 {
00111 pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_);
00112
00113 boost::function<void (const CloudConstPtr&)> f = boost::bind (&OpenNIFastMesh::cloud_cb, this, _1);
00114 boost::signals2::connection c = interface->registerCallback (f);
00115
00116 view.reset (new pcl::visualization::PCLVisualizer (argc, argv, "PCL OpenNI Mesh Viewer"));
00117
00118 interface->start ();
00119
00120 CloudConstPtr temp_cloud;
00121 boost::shared_ptr<std::vector<pcl::Vertices> > temp_verts;
00122 pcl::console::TicToc t1;
00123
00124 while (!view->wasStopped ())
00125
00126 {
00127
00128 if (!cloud_ || !mtx_.try_lock ())
00129 {
00130 boost::this_thread::sleep (boost::posix_time::milliseconds (1));
00131 continue;
00132 }
00133
00134
00135
00136
00137 temp_cloud = cloud_;
00138 temp_verts = vertices_;
00139 mtx_.unlock ();
00140
00141
00142 if (!view->updatePolygonMesh<PointType> (temp_cloud, *temp_verts, "surface"))
00143 {
00144 view->addPolygonMesh<PointType> (temp_cloud, *temp_verts, "surface");
00145
00146 }
00147
00148 FPS_CALC ("visualization");
00149 view->spinOnce (1);
00150 }
00151
00152 interface->stop ();
00153 }
00154
00155 pcl::OrganizedFastMesh<PointType> ofm;
00156 std::string device_id_;
00157
00158 boost::mutex mtx_;
00159
00160 CloudConstPtr cloud_;
00161 boost::shared_ptr<std::vector<pcl::Vertices> > vertices_;
00162 pcl::PolygonMesh::Ptr mesh_;
00163
00164 boost::shared_ptr<pcl::visualization::PCLVisualizer> view;
00165 };
00166
00167 void
00168 usage (char ** argv)
00169 {
00170 std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n";
00171
00172 openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00173 if (driver.getNumberDevices () > 0)
00174 {
00175 for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
00176 {
00177 cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
00178 << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
00179 cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << endl
00180 << " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << endl
00181 << " <serial-number> (only in Linux and for devices which provide serial numbers)" << endl;
00182 }
00183 }
00184 else
00185 cout << "No devices connected." << endl;
00186 }
00187
00188 int
00189 main (int argc, char ** argv)
00190 {
00191 std::string arg;
00192 if (argc > 1)
00193 arg = std::string (argv[1]);
00194
00195 if (arg == "--help" || arg == "-h")
00196 {
00197 usage (argv);
00198 return 1;
00199 }
00200
00201 pcl::OpenNIGrabber grabber ("");
00202 if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba> ())
00203 {
00204 PCL_INFO ("PointXYZRGBA mode enabled.\n");
00205 OpenNIFastMesh<pcl::PointXYZRGBA> v ("");
00206 v.run (argc, argv);
00207 }
00208 else
00209 {
00210 PCL_INFO ("PointXYZ mode enabled.\n");
00211 OpenNIFastMesh<pcl::PointXYZ> v ("");
00212 v.run (argc, argv);
00213 }
00214 return (0);
00215 }