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