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 #include <pcl/io/io.h>
00036 #include <pcl/io/pcd_io.h>
00037 #include <pcl/visualization/pcl_visualizer.h>
00038 #include <pcl/common/time.h>
00039 #include <pcl/features/integral_image_normal.h>
00040 #include <pcl/features/normal_3d.h>
00041 #include <pcl/ModelCoefficients.h>
00042 #include <pcl/segmentation/planar_region.h>
00043 #include <pcl/segmentation/organized_multi_plane_segmentation.h>
00044 #include <pcl/segmentation/organized_connected_component_segmentation.h>
00045 #include <pcl/filters/extract_indices.h>
00046 #include <pcl/console/parse.h>
00047 #include <pcl/geometry/polygon_operations.h>
00048
00049 template<typename PointT>
00050 class PCDOrganizedMultiPlaneSegmentation
00051 {
00052 private:
00053 pcl::visualization::PCLVisualizer viewer;
00054 typename pcl::PointCloud<PointT>::ConstPtr cloud;
00055 bool refine_;
00056 float threshold_;
00057 bool depth_dependent_;
00058 bool polygon_refinement_;
00059 public:
00060 PCDOrganizedMultiPlaneSegmentation (typename pcl::PointCloud<PointT>::ConstPtr cloud_, bool refine)
00061 : viewer ("Viewer")
00062 , cloud (cloud_)
00063 , refine_ (refine)
00064 , threshold_ (0.02f)
00065 , depth_dependent_ (true)
00066 , polygon_refinement_ (false)
00067 {
00068 viewer.setBackgroundColor (0, 0, 0);
00069
00070
00071 viewer.addCoordinateSystem (1.0);
00072 viewer.initCameraParameters ();
00073 viewer.registerKeyboardCallback(&PCDOrganizedMultiPlaneSegmentation::keyboard_callback, *this, 0);
00074 }
00075
00076 void keyboard_callback (const pcl::visualization::KeyboardEvent& event, void*)
00077 {
00078
00079 if (event.keyUp ())
00080 {
00081 switch (event.getKeyCode ())
00082 {
00083 case 'b':
00084 case 'B':
00085 if (threshold_ < 0.1f)
00086 threshold_ += 0.001f;
00087 process ();
00088 break;
00089 case 'v':
00090 case 'V':
00091 if (threshold_ > 0.001f)
00092 threshold_ -= 0.001f;
00093 process ();
00094 break;
00095
00096 case 'n':
00097 case 'N':
00098 depth_dependent_ = !depth_dependent_;
00099 process ();
00100 break;
00101
00102 case 'm':
00103 case 'M':
00104 polygon_refinement_ = !polygon_refinement_;
00105 process ();
00106 break;
00107 }
00108 }
00109 }
00110
00111 void
00112 process ()
00113 {
00114 std::cout << "threshold: " << threshold_ << std::endl;
00115 std::cout << "depth dependent: " << (depth_dependent_ ? "true\n" : "false\n");
00116 unsigned char red [6] = {255, 0, 0, 255, 255, 0};
00117 unsigned char grn [6] = { 0, 255, 0, 255, 0, 255};
00118 unsigned char blu [6] = { 0, 0, 255, 0, 255, 255};
00119
00120 pcl::IntegralImageNormalEstimation<PointT, pcl::Normal> ne;
00121 ne.setNormalEstimationMethod (ne.COVARIANCE_MATRIX);
00122 ne.setMaxDepthChangeFactor (0.02f);
00123 ne.setNormalSmoothingSize (20.0f);
00124
00125 typename pcl::PlaneRefinementComparator<PointT, pcl::Normal, pcl::Label>::Ptr refinement_compare (new pcl::PlaneRefinementComparator<PointT, pcl::Normal, pcl::Label> ());
00126 refinement_compare->setDistanceThreshold (threshold_, depth_dependent_);
00127
00128 pcl::OrganizedMultiPlaneSegmentation<PointT, pcl::Normal, pcl::Label> mps;
00129 mps.setMinInliers (5000);
00130 mps.setAngularThreshold (0.017453 * 3.0);
00131 mps.setDistanceThreshold (0.03);
00132 mps.setRefinementComparator (refinement_compare);
00133
00134 std::vector<pcl::PlanarRegion<PointT>, Eigen::aligned_allocator<pcl::PlanarRegion<PointT> > > regions;
00135 typename pcl::PointCloud<PointT>::Ptr contour (new pcl::PointCloud<PointT>);
00136 typename pcl::PointCloud<PointT>::Ptr approx_contour (new pcl::PointCloud<PointT>);
00137 char name[1024];
00138
00139 typename pcl::PointCloud<pcl::Normal>::Ptr normal_cloud (new pcl::PointCloud<pcl::Normal>);
00140 double normal_start = pcl::getTime ();
00141 ne.setInputCloud (cloud);
00142 ne.compute (*normal_cloud);
00143 double normal_end = pcl::getTime ();
00144 std::cout << "Normal Estimation took " << double (normal_end - normal_start) << std::endl;
00145
00146 double plane_extract_start = pcl::getTime ();
00147 mps.setInputNormals (normal_cloud);
00148 mps.setInputCloud (cloud);
00149 if (refine_)
00150 mps.segmentAndRefine (regions);
00151 else
00152 mps.segment (regions);
00153 double plane_extract_end = pcl::getTime ();
00154 std::cout << "Plane extraction took " << double (plane_extract_end - plane_extract_start) << " with planar regions found: " << regions.size () << std::endl;
00155 std::cout << "Frame took " << double (plane_extract_end - normal_start) << std::endl;
00156
00157 typename pcl::PointCloud<PointT>::Ptr cluster (new pcl::PointCloud<PointT>);
00158
00159 viewer.removeAllPointClouds (0);
00160 viewer.removeAllShapes (0);
00161 pcl::visualization::PointCloudColorHandlerCustom<PointT> single_color (cloud, 0, 255, 0);
00162 viewer.addPointCloud<PointT> (cloud, single_color, "cloud");
00163
00164 pcl::PlanarPolygon<PointT> approx_polygon;
00165
00166 for (size_t i = 0; i < regions.size (); i++)
00167 {
00168 Eigen::Vector3f centroid = regions[i].getCentroid ();
00169 Eigen::Vector4f model = regions[i].getCoefficients ();
00170 pcl::PointXYZ pt1 = pcl::PointXYZ (centroid[0], centroid[1], centroid[2]);
00171 pcl::PointXYZ pt2 = pcl::PointXYZ (centroid[0] + (0.5f * model[0]),
00172 centroid[1] + (0.5f * model[1]),
00173 centroid[2] + (0.5f * model[2]));
00174 sprintf (name, "normal_%d", unsigned (i));
00175 viewer.addArrow (pt2, pt1, 1.0, 0, 0, std::string (name));
00176
00177 contour->points = regions[i].getContour ();
00178 sprintf (name, "plane_%02d", int (i));
00179 pcl::visualization::PointCloudColorHandlerCustom <PointT> color (contour, red[i], grn[i], blu[i]);
00180 viewer.addPointCloud (contour, color, name);
00181
00182 pcl::approximatePolygon (regions[i], approx_polygon, threshold_, polygon_refinement_);
00183 approx_contour->points = approx_polygon.getContour ();
00184 std::cout << "polygon: " << contour->size () << " -> " << approx_contour->size () << std::endl;
00185 typename pcl::PointCloud<PointT>::ConstPtr approx_contour_const = approx_contour;
00186
00187
00188
00189 for (unsigned idx = 0; idx < approx_contour->points.size (); ++idx)
00190 {
00191 sprintf (name, "approx_plane_%02d_%03d", int (i), int(idx));
00192 viewer.addLine (approx_contour->points [idx], approx_contour->points [(idx+1)%approx_contour->points.size ()], 0.5 * red[i], 0.5 * grn[i], 0.5 * blu[i], name);
00193 }
00194 }
00195 }
00196
00197 void
00198 run ()
00199 {
00200
00201 process ();
00202
00203 while (!viewer.wasStopped ())
00204 viewer.spinOnce (100);
00205 }
00206 };
00207
00208 int
00209 main (int argc, char** argv)
00210 {
00211 bool refine = pcl::console::find_switch (argc, argv, "-refine");
00212
00213 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_xyz (new pcl::PointCloud<pcl::PointXYZ>);
00214 pcl::io::loadPCDFile (argv[1], *cloud_xyz);
00215 PCDOrganizedMultiPlaneSegmentation<pcl::PointXYZ> multi_plane_app (cloud_xyz, refine);
00216 multi_plane_app.run ();
00217 return 0;
00218 }