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/project_inliers.h>
00049 #include <pcl/surface/convex_hull.h>
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 Hull Segmentation Viewer"),
00061 device_id_ (device_id)
00062 {
00063 grid_.setFilterFieldName ("z");
00064 grid_.setFilterLimits (0.0, 3.0);
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 proj_.setModelType (pcl::SACMODEL_PLANE);
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
00108 proj_.setInputCloud (temp_cloud);
00109 proj_.setModelCoefficients (coefficients);
00110 proj_.filter (*temp_cloud2);
00111
00112
00113 chull_.setInputCloud (temp_cloud2);
00114 chull_.reconstruct (*temp_cloud);
00115
00116 return (temp_cloud);
00117 }
00118
00119 void
00120 run ()
00121 {
00122 pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_);
00123
00124 boost::function<void (const CloudConstPtr&)> f = boost::bind (&OpenNIPlanarSegmentation::cloud_cb_, this, _1);
00125 boost::signals2::connection c = interface->registerCallback (f);
00126
00127 interface->start ();
00128
00129 while (!viewer.wasStopped ())
00130 {
00131 if (cloud_)
00132 {
00133
00134 viewer.showCloud (get ());
00135 }
00136 }
00137
00138 interface->stop ();
00139 }
00140
00141 pcl::visualization::CloudViewer viewer;
00142 pcl::VoxelGrid<PointType> grid_;
00143 pcl::SACSegmentation<PointType> seg_;
00144 pcl::ProjectInliers<PointType> proj_;
00145 pcl::ConvexHull<PointType> chull_;
00146
00147 std::string device_id_;
00148 boost::mutex mtx_;
00149 CloudConstPtr cloud_;
00150 };
00151
00152 void
00153 usage (char ** argv)
00154 {
00155 std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n"
00156 << "where options are:\n -thresh X :: set the planar segmentation threshold (default: 0.5)\n";
00157
00158 openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00159 if (driver.getNumberDevices () > 0)
00160 {
00161 for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
00162 {
00163 cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
00164 << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
00165 cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << endl
00166 << " bus@address for the device connected to a specific usb-bus / address combination (wotks only in Linux) or" << endl
00167 << " <serial-number> (only in Linux and for devices which provide serial numbers)" << endl;
00168 }
00169 }
00170 else
00171 cout << "No devices connected." << endl;
00172 }
00173
00174 int
00175 main (int argc, char ** argv)
00176 {
00177 if (argc < 2)
00178 {
00179 usage (argv);
00180 return 1;
00181 }
00182
00183 std::string arg (argv[1]);
00184
00185 if (arg == "--help" || arg == "-h")
00186 {
00187 usage (argv);
00188 return 1;
00189 }
00190
00191 double threshold = 0.05;
00192 pcl::console::parse_argument (argc, argv, "-thresh", threshold);
00193
00194 pcl::OpenNIGrabber grabber (arg);
00195 if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba> ())
00196 {
00197 OpenNIPlanarSegmentation<pcl::PointXYZRGBA> v (arg, threshold);
00198 v.run ();
00199 }
00200 else
00201 {
00202 OpenNIPlanarSegmentation<pcl::PointXYZ> v (arg, threshold);
00203 v.run ();
00204 }
00205
00206 return (0);
00207 }