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/visualization/cloud_viewer.h>
00042 #include <pcl/io/openni_camera/openni_driver.h>
00043 #include <pcl/keypoints/uniform_sampling.h>
00044 #include <pcl/console/parse.h>
00045 #include <pcl/common/time.h>
00046
00047 #define FPS_CALC(_WHAT_) \
00048 do \
00049 { \
00050 static unsigned count = 0;\
00051 static double last = pcl::getTime ();\
00052 double now = pcl::getTime (); \
00053 ++count; \
00054 if (now - last >= 1.0) \
00055 { \
00056 std::cout << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz" << std::endl; \
00057 count = 0; \
00058 last = now; \
00059 } \
00060 }while(false)
00061
00062
00063 class OpenNIUniformSampling
00064 {
00065 public:
00066 typedef pcl::PointCloud<pcl::PointXYZRGBA> Cloud;
00067 typedef Cloud::Ptr CloudPtr;
00068 typedef Cloud::ConstPtr CloudConstPtr;
00069
00070 OpenNIUniformSampling (const std::string& device_id = "",
00071 float leaf_size = 0.05)
00072 : viewer ("PCL OpenNI PassThrough Viewer")
00073 , device_id_(device_id)
00074 {
00075 pass_.setRadiusSearch (leaf_size);
00076 }
00077
00078 void
00079 cloud_cb_ (const CloudConstPtr& cloud)
00080 {
00081 boost::mutex::scoped_lock lock (mtx_);
00082 FPS_CALC ("computation");
00083
00084 cloud_.reset (new Cloud);
00085 indices_.reset (new pcl::PointCloud<int>);
00086 keypoints_.reset (new pcl::PointCloud<pcl::PointXYZ>);
00087
00088 pass_.setInputCloud (cloud);
00089 pass_.compute (*indices_);
00090 *cloud_ = *cloud;
00091
00092 pcl::copyPointCloud<pcl::PointXYZRGBA, pcl::PointXYZ> (*cloud, indices_->points, *keypoints_);
00093 }
00094
00095 void
00096 viz_cb (pcl::visualization::PCLVisualizer& viz)
00097 {
00098 boost::mutex::scoped_lock lock (mtx_);
00099 if (!keypoints_ && !cloud_)
00100 {
00101 boost::this_thread::sleep(boost::posix_time::seconds(1));
00102 return;
00103 }
00104
00105 FPS_CALC ("visualization");
00106 viz.removePointCloud ("raw");
00107 pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGBA> color_handler (cloud_);
00108 viz.addPointCloud<pcl::PointXYZRGBA> (cloud_, color_handler, "raw");
00109
00110 if (!viz.updatePointCloud<pcl::PointXYZ> (keypoints_, "keypoints"))
00111 {
00112 viz.addPointCloud<pcl::PointXYZ> (keypoints_, "keypoints");
00113 viz.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 5.0, "keypoints");
00114 viz.resetCameraViewpoint ("keypoints");
00115 }
00116 }
00117
00118 void
00119 run ()
00120 {
00121 pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_);
00122
00123 boost::function<void (const CloudConstPtr&)> f = boost::bind (&OpenNIUniformSampling::cloud_cb_, this, _1);
00124 boost::signals2::connection c = interface->registerCallback (f);
00125 viewer.runOnVisualizationThread (boost::bind(&OpenNIUniformSampling::viz_cb, this, _1), "viz_cb");
00126
00127 interface->start ();
00128
00129 while (!viewer.wasStopped ())
00130 {
00131 boost::this_thread::sleep(boost::posix_time::seconds(1));
00132 }
00133
00134 interface->stop ();
00135 }
00136
00137 pcl::UniformSampling<pcl::PointXYZRGBA> pass_;
00138 pcl::visualization::CloudViewer viewer;
00139 std::string device_id_;
00140 boost::mutex mtx_;
00141 CloudPtr cloud_;
00142 pcl::PointCloud<pcl::PointXYZ>::Ptr keypoints_;
00143 pcl::PointCloud<int>::Ptr indices_;
00144 };
00145
00146 void
00147 usage (char ** argv)
00148 {
00149 std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n"
00150 << "where options are:\n"
00151 << " -leaf X :: set the UniformSampling leaf size (default: 0.01)\n";
00152
00153 openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00154 if (driver.getNumberDevices () > 0)
00155 {
00156 for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
00157 {
00158 cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
00159 << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
00160 cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << endl
00161 << " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << endl
00162 << " <serial-number> (only in Linux and for devices which provide serial numbers)" << endl;
00163 }
00164 }
00165 else
00166 cout << "No devices connected." << endl;
00167 }
00168
00169 int
00170 main (int argc, char ** argv)
00171 {
00172 if (argc < 2)
00173 {
00174 usage (argv);
00175 return 1;
00176 }
00177
00178 std::string arg (argv[1]);
00179
00180 if (arg == "--help" || arg == "-h")
00181 {
00182 usage (argv);
00183 return 1;
00184 }
00185
00186 float leaf_res = 0.05f;
00187 pcl::console::parse_argument (argc, argv, "-leaf", leaf_res);
00188 PCL_INFO ("Using %f as a leaf size for UniformSampling.\n", leaf_res);
00189
00190 pcl::OpenNIGrabber grabber (arg);
00191 OpenNIUniformSampling v (arg, leaf_res);
00192 v.run ();
00193
00194 return (0);
00195 }