openni_range_image_visualization.cpp
Go to the documentation of this file.
00001 /* \author Bastian Steder */
00002 
00003 /* ---[ */
00004 #include <iostream>
00005 using namespace std;
00006 #include <pcl/io/openni_grabber.h>
00007 #include <pcl/range_image/range_image_planar.h>
00008 #include <pcl/common/common_headers.h>
00009 #include <pcl/visualization/range_image_visualizer.h>
00010 #include <pcl/visualization/pcl_visualizer.h>
00011 #include <pcl/console/parse.h>
00012 
00013 std::string device_id = "#1";
00014 
00015 float angular_resolution = -1.0f;
00016 
00017 boost::mutex depth_image_mutex;
00018 boost::shared_ptr<openni_wrapper::DepthImage> depth_image_ptr;
00019 bool received_new_depth_data = false;
00020 
00021 struct EventHelper
00022 {
00023   void
00024   depth_image_cb (const boost::shared_ptr<openni_wrapper::DepthImage>& depth_image)
00025   {
00026     if (depth_image_mutex.try_lock ())
00027     {
00028       depth_image_ptr = depth_image;
00029       depth_image_mutex.unlock ();
00030       received_new_depth_data = true;
00031     }
00032   }
00033 };
00034 
00035 void
00036 printUsage (const char* progName)
00037 {
00038   cout << "\n\nUsage: "<<progName<<" [options] [scene.pcd] <model.pcl> [model_2.pcl] ... [model_n.pcl]\n\n"
00039        << "Options:\n"
00040        << "-------------------------------------------\n"
00041        << "-d <device_id>  set the device id (default \""<<device_id<<"\")\n"
00042        << "-r <float>      angular resolution in degrees (default "<<angular_resolution<<")\n"
00043        << "-h              this help\n"
00044        << "\n\n";
00045 }
00046 
00047 int main (int argc, char** argv)
00048 {
00049   // --------------------------------------
00050   // -----Parse Command Line Arguments-----
00051   // --------------------------------------
00052   if (pcl::console::find_argument (argc, argv, "-h") >= 0)
00053   {
00054     printUsage (argv[0]);
00055     return 0;
00056   }
00057   if (pcl::console::parse (argc, argv, "-d", device_id) >= 0)
00058     cout << "Using device id \""<<device_id<<"\".\n";
00059   if (pcl::console::parse (argc, argv, "-r", angular_resolution) >= 0)
00060     cout << "Setting angular resolution to "<<angular_resolution<<"deg.\n";
00061   angular_resolution = pcl::deg2rad (angular_resolution);
00062   
00063   pcl::visualization::RangeImageVisualizer range_image_widget ("Range Image");
00064   
00065   pcl::visualization::PCLVisualizer viewer ("3D Viewer");
00066   viewer.addCoordinateSystem (1.0f);
00067   viewer.setBackgroundColor (1, 1, 1);
00068   
00069   // Set the viewing pose so that the openni cloud is visible
00070   viewer.initCameraParameters ();
00071    viewer.setCameraPosition (0.0, -0.3, -2.0,
00072                             0.0, -0.3, 1.0,
00073                             0.0, -1.0, 0.0);
00074   
00075   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00076   if (driver.getNumberDevices () > 0)
00077   {
00078     for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
00079     {
00080       cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx)
00081            << ", product: " << driver.getProductName (deviceIdx) << ", connected: "
00082            << (int) driver.getBus (deviceIdx) << " @ " << (int) driver.getAddress (deviceIdx)
00083            << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'\n";
00084     }
00085   }
00086   else
00087   {
00088     cout << "\nNo devices connected.\n\n";
00089     return 1;
00090   }
00091   
00092   pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id);
00093   EventHelper event_helper;
00094   
00095   boost::function<void (const boost::shared_ptr<openni_wrapper::DepthImage>&) > f_depth_image =
00096     boost::bind (&EventHelper::depth_image_cb, &event_helper, _1);
00097   boost::signals2::connection c_depth_image = interface->registerCallback (f_depth_image);
00098   
00099   cout << "Starting grabber\n";
00100   interface->start ();
00101   cout << "Done\n";
00102   
00103   boost::shared_ptr<pcl::RangeImagePlanar> range_image_planar_ptr (new pcl::RangeImagePlanar);
00104   pcl::RangeImagePlanar& range_image_planar = *range_image_planar_ptr;
00105   
00106   while (!viewer.wasStopped ())
00107   {
00108     viewer.spinOnce ();  // process 3D Viewer events
00109     range_image_widget.spinOnce ();  // process Image Viewer events
00110     pcl_sleep (0.01);
00111     
00112     bool got_new_range_image = false;
00113     if (received_new_depth_data && depth_image_mutex.try_lock ())
00114     {
00115       received_new_depth_data = false;
00116 
00117       int frame_id = depth_image_ptr->getFrameID ();
00118       cout << "Visualizing frame "<<frame_id<<"\n";
00119       const unsigned short* depth_map = depth_image_ptr->getDepthMetaData ().Data ();
00120       int width = depth_image_ptr->getWidth (), height = depth_image_ptr->getHeight ();
00121       float center_x = width/2, center_y = height/2;
00122       float focal_length_x = depth_image_ptr->getFocalLength (), focal_length_y = focal_length_x;
00123       float original_angular_resolution = asinf (0.5f*float (width)/float (focal_length_x)) / (0.5f*float (width));
00124       float desired_angular_resolution = angular_resolution;
00125       range_image_planar.setDepthImage (depth_map, width, height, center_x, center_y,
00126                                         focal_length_x, focal_length_y, desired_angular_resolution);
00127       depth_image_mutex.unlock ();
00128       got_new_range_image = !range_image_planar.points.empty ();
00129     }
00130     
00131     if (!got_new_range_image)
00132       continue;
00133     
00134     // Show range image in the image widget
00135     range_image_widget.showRangeImage (range_image_planar, 0.5f, 10.0f);
00136     
00137     // Show range image in the 3D viewer
00138     pcl::visualization::PointCloudColorHandlerCustom<pcl::PointWithRange> color_handler_cloud
00139       (range_image_planar_ptr, 0, 0, 0);
00140     if (!viewer.updatePointCloud<pcl::PointWithRange> (range_image_planar_ptr, color_handler_cloud, "range image"))
00141       viewer.addPointCloud<pcl::PointWithRange> (range_image_planar_ptr, color_handler_cloud, "range image");
00142   }
00143 
00144   interface->stop ();
00145 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:26:52