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/features/integral_image_normal.h>
00042 #include <pcl/console/parse.h>
00043 #include <pcl/common/time.h>
00044 #include <pcl/visualization/cloud_viewer.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 } \
00059 }while(false)
00060
00061 template <typename PointType>
00062 class OpenNIIntegralImageNormalEstimation
00063 {
00064 public:
00065 typedef pcl::PointCloud<PointType> Cloud;
00066 typedef typename Cloud::Ptr CloudPtr;
00067 typedef typename Cloud::ConstPtr CloudConstPtr;
00068
00069 OpenNIIntegralImageNormalEstimation (const std::string& device_id = "")
00070 : viewer ("PCL OpenNI NormalEstimation Viewer")
00071 , device_id_(device_id)
00072 {
00073
00074 ne_.setNormalEstimationMethod (pcl::IntegralImageNormalEstimation<PointType, pcl::Normal>::COVARIANCE_MATRIX);
00075 ne_.setNormalSmoothingSize (11.0);
00076 new_cloud_ = false;
00077 viewer.registerKeyboardCallback(&OpenNIIntegralImageNormalEstimation::keyboard_callback, *this);
00078 }
00079
00080
00081 void
00082 cloud_cb (const CloudConstPtr& cloud)
00083 {
00084 boost::mutex::scoped_lock lock (mtx_);
00085
00086
00087
00088
00089 normals_.reset (new pcl::PointCloud<pcl::Normal>);
00090
00091
00092 ne_.setInputCloud (cloud);
00093 ne_.compute (*normals_);
00094
00095
00096 cloud_ = cloud;
00097
00098 new_cloud_ = true;
00099 }
00100
00101 void
00102 viz_cb (pcl::visualization::PCLVisualizer& viz)
00103 {
00104 mtx_.lock ();
00105 if (!cloud_ || !normals_)
00106 {
00107
00108 mtx_.unlock ();
00109 return;
00110 }
00111
00112 CloudConstPtr temp_cloud;
00113 pcl::PointCloud<pcl::Normal>::Ptr temp_normals;
00114 temp_cloud.swap (cloud_);
00115 temp_normals.swap (normals_);
00116 mtx_.unlock ();
00117
00118 if (!viz.updatePointCloud (temp_cloud, "OpenNICloud"))
00119 {
00120 viz.addPointCloud (temp_cloud, "OpenNICloud");
00121 viz.resetCameraViewpoint ("OpenNICloud");
00122 }
00123
00124 if (new_cloud_)
00125 {
00126 viz.removePointCloud ("normalcloud");
00127 viz.addPointCloudNormals<PointType, pcl::Normal> (temp_cloud, temp_normals, 100, 0.05f, "normalcloud");
00128 new_cloud_ = false;
00129 }
00130 }
00131
00132 void
00133 keyboard_callback (const pcl::visualization::KeyboardEvent& event, void*)
00134 {
00135 boost::mutex::scoped_lock lock (mtx_);
00136 switch (event.getKeyCode ())
00137 {
00138 case '1':
00139 ne_.setNormalEstimationMethod (pcl::IntegralImageNormalEstimation<PointType, pcl::Normal>::COVARIANCE_MATRIX);
00140 std::cout << "switched to COVARIANCE_MATRIX method\n";
00141 break;
00142 case '2':
00143 ne_.setNormalEstimationMethod (pcl::IntegralImageNormalEstimation<PointType, pcl::Normal>::AVERAGE_3D_GRADIENT);
00144 std::cout << "switched to AVERAGE_3D_GRADIENT method\n";
00145 break;
00146 case '3':
00147 ne_.setNormalEstimationMethod (pcl::IntegralImageNormalEstimation<PointType, pcl::Normal>::AVERAGE_DEPTH_CHANGE);
00148 std::cout << "switched to AVERAGE_DEPTH_CHANGE method\n";
00149 break;
00150 case '4':
00151 ne_.setNormalEstimationMethod (pcl::IntegralImageNormalEstimation<PointType, pcl::Normal>::SIMPLE_3D_GRADIENT);
00152 std::cout << "switched to SIMPLE_3D_GRADIENT method\n";
00153 break;
00154 }
00155 }
00156
00157 void
00158 run ()
00159 {
00160 pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_);
00161
00162 boost::function<void (const CloudConstPtr&)> f = boost::bind (&OpenNIIntegralImageNormalEstimation::cloud_cb, this, _1);
00163 boost::signals2::connection c = interface->registerCallback (f);
00164
00165 viewer.runOnVisualizationThread (boost::bind(&OpenNIIntegralImageNormalEstimation::viz_cb, this, _1), "viz_cb");
00166
00167 interface->start ();
00168
00169 while (!viewer.wasStopped ())
00170 {
00171 boost::this_thread::sleep(boost::posix_time::seconds(1));
00172 }
00173
00174 interface->stop ();
00175 }
00176
00177 pcl::IntegralImageNormalEstimation<PointType, pcl::Normal> ne_;
00178 pcl::visualization::CloudViewer viewer;
00179 std::string device_id_;
00180 boost::mutex mtx_;
00181
00182 pcl::PointCloud<pcl::Normal>::Ptr normals_;
00183 CloudConstPtr cloud_;
00184 bool new_cloud_;
00185 };
00186
00187 void
00188 usage (char ** argv)
00189 {
00190 std::cout << "usage: " << argv[0] << " [<device_id>]\n\n";
00191
00192 openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00193 if (driver.getNumberDevices () > 0)
00194 {
00195 for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
00196 {
00197 cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
00198 << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
00199 cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << endl
00200 << " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << endl
00201 << " <serial-number> (only in Linux and for devices which provide serial numbers)" << endl;
00202 }
00203 }
00204 else
00205 cout << "No devices connected." << endl;
00206 }
00207
00208 int
00209 main (int argc, char ** argv)
00210 {
00211 std::string arg;
00212 if (argc > 1)
00213 arg = std::string (argv[1]);
00214
00215 openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00216 if (arg == "--help" || arg == "-h" || driver.getNumberDevices () == 0)
00217 {
00218 usage (argv);
00219 return 1;
00220 }
00221
00222 std::cout << "Press following keys to switch to the different integral image normal estimation methods:\n";
00223 std::cout << "<1> COVARIANCE_MATRIX method\n";
00224 std::cout << "<2> AVERAGE_3D_GRADIENT method\n";
00225 std::cout << "<3> AVERAGE_DEPTH_CHANGE method\n";
00226 std::cout << "<4> SIMPLE_3D_GRADIENT method\n";
00227 std::cout << "<Q,q> quit\n\n";
00228
00229 pcl::OpenNIGrabber grabber ("");
00230 if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba> ())
00231 {
00232 PCL_INFO ("PointXYZRGBA mode enabled.\n");
00233 OpenNIIntegralImageNormalEstimation<pcl::PointXYZRGBA> v ("");
00234 v.run ();
00235 }
00236 else
00237 {
00238 PCL_INFO ("PointXYZ mode enabled.\n");
00239 OpenNIIntegralImageNormalEstimation<pcl::PointXYZ> v ("");
00240 v.run ();
00241 }
00242
00243 return (0);
00244 }