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/console/parse.h>
00044 #include <pcl/sample_consensus/method_types.h>
00045 #include <pcl/sample_consensus/model_types.h>
00046 #include <pcl/segmentation/sac_segmentation.h>
00047 #include <pcl/filters/voxel_grid.h>
00048 #include <pcl/filters/extract_indices.h>
00049
00050
00051 template <typename PointType>
00052 class OpenNIPlanarSegmentation
00053 {
00054 public:
00055 typedef pcl::PointCloud<PointType> Cloud;
00056 typedef typename Cloud::Ptr CloudPtr;
00057 typedef typename Cloud::ConstPtr CloudConstPtr;
00058
00059 OpenNIPlanarSegmentation (const std::string& device_id = "", double threshold = 0.01)
00060 : viewer ("PCL OpenNI Planar Segmentation Viewer"),
00061 device_id_ (device_id)
00062 {
00063 grid_.setFilterFieldName ("z");
00064 grid_.setFilterLimits (0.0f, 3.0f);
00065 grid_.setLeafSize (0.01f, 0.01f, 0.01f);
00066
00067 seg_.setOptimizeCoefficients (true);
00068 seg_.setModelType (pcl::SACMODEL_PLANE);
00069 seg_.setMethodType (pcl::SAC_RANSAC);
00070 seg_.setMaxIterations (1000);
00071 seg_.setDistanceThreshold (threshold);
00072
00073 extract_.setNegative (false);
00074 }
00075
00076 void
00077 cloud_cb_ (const CloudConstPtr& cloud)
00078 {
00079 set (cloud);
00080 }
00081
00082 void
00083 set (const CloudConstPtr& cloud)
00084 {
00085
00086 boost::mutex::scoped_lock lock (mtx_);
00087 cloud_ = cloud;
00088 }
00089
00090 CloudPtr
00091 get ()
00092 {
00093
00094 boost::mutex::scoped_lock lock (mtx_);
00095 CloudPtr temp_cloud (new Cloud);
00096 CloudPtr temp_cloud2 (new Cloud);
00097
00098 grid_.setInputCloud (cloud_);
00099 grid_.filter (*temp_cloud);
00100
00101 pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients ());
00102 pcl::PointIndices::Ptr inliers (new pcl::PointIndices ());
00103
00104 seg_.setInputCloud (temp_cloud);
00105 seg_.segment (*inliers, *coefficients);
00106
00107 extract_.setInputCloud (temp_cloud);
00108 extract_.setIndices (inliers);
00109 extract_.filter (*temp_cloud2);
00110
00111 return (temp_cloud2);
00112 }
00113
00114 void
00115 run ()
00116 {
00117 pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_);
00118
00119 boost::function<void (const CloudConstPtr&)> f = boost::bind (&OpenNIPlanarSegmentation::cloud_cb_, this, _1);
00120 boost::signals2::connection c = interface->registerCallback (f);
00121
00122 interface->start ();
00123
00124 while (!viewer.wasStopped ())
00125 {
00126 if (cloud_)
00127 {
00128
00129 viewer.showCloud (get ());
00130 }
00131 }
00132
00133 interface->stop ();
00134 }
00135
00136 pcl::visualization::CloudViewer viewer;
00137 pcl::VoxelGrid<PointType> grid_;
00138 pcl::SACSegmentation<PointType> seg_;
00139 pcl::ExtractIndices<PointType> extract_;
00140
00141 std::string device_id_;
00142 boost::mutex mtx_;
00143 CloudConstPtr cloud_;
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 -thresh X :: set the planar segmentation threshold (default: 0.5)\n";
00151
00152 openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00153 if (driver.getNumberDevices () > 0)
00154 {
00155 for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
00156 {
00157 cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
00158 << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
00159 cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << endl
00160 << " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << endl
00161 << " <serial-number> (only in Linux and for devices which provide serial numbers)" << endl;
00162 }
00163 }
00164 else
00165 cout << "No devices connected." << endl;
00166 }
00167
00168 int
00169 main (int argc, char ** argv)
00170 {
00171 if (argc < 2)
00172 {
00173 usage (argv);
00174 return 1;
00175 }
00176
00177 std::string arg (argv[1]);
00178
00179 if (arg == "--help" || arg == "-h")
00180 {
00181 usage (argv);
00182 return 1;
00183 }
00184
00185 double threshold = 0.05;
00186 pcl::console::parse_argument (argc, argv, "-thresh", threshold);
00187
00188 pcl::OpenNIGrabber grabber (arg);
00189 if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba> ())
00190 {
00191 OpenNIPlanarSegmentation<pcl::PointXYZRGBA> v (arg, threshold);
00192 v.run ();
00193 }
00194 else
00195 {
00196 OpenNIPlanarSegmentation<pcl::PointXYZ> v (arg, threshold);
00197 v.run ();
00198 }
00199
00200 return (0);
00201 }