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